From 71706f0600732ee2f6730511ac13bf9ed2c101a3 Mon Sep 17 00:00:00 2001 From: caijie <1250648467@qq.com> Date: Tue, 24 Sep 2024 14:28:37 +0800 Subject: [PATCH] AP_HAL_ChibiOS: add VUAV-V7pro --- .../AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md | 608 ++++++++++++++++++ .../hwdef/VUAV-V7pro/VUAV-V7pro-interface.png | Bin 0 -> 56034 bytes .../hwdef/VUAV-V7pro/VUAV-V7pro-pinout.png | Bin 0 -> 114542 bytes .../hwdef/VUAV-V7pro/defaults.parm | 5 + .../hwdef/VUAV-V7pro/hwdef-bl.dat | 79 +++ .../AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat | 286 ++++++++ 6 files changed, 978 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-interface.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-pinout.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md new file mode 100644 index 0000000000..59063de301 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/README.md @@ -0,0 +1,608 @@ +# VUAV-V7pro Flight Controller + +The VUAV-V7pro flight controller is manufactured and sold by [VIEWPRO](http://www.viewprotech.com/). + +## Features + + - STM32H743 microcontroller + - Three IMUs: ADIS16470,ICM42688,ICM42688 + - Internal vibration isolation for IMUs + - Internal RM3100 SPI magnetometer + - Internal two MS5611 SPI barometer + - Internal RGB LED + - MicroSD card slot port + - 1 Analog power port + - 1 CAN power port + - 5 UARTs and 1 USB ports + - 1 RS232 port + - 14 PWM output ports + - 4 I2C and 2 CAN ports + - Safety switch port + - Buzzer port + - RC IN port + +## Pinout + +![VUAV-V7pro-interface.png](VUAV-V7pro-interface.png) + +![VUAV-V7pro-pinout.png](VUAV-V7pro-pinout.png) + +## UART Mapping + - SERIAL0 -> USB + - SERIAL1 -> UART2 (Telem1) (DMA enabled) + - SERIAL2 -> UART6 (Telem2) (DMA enabled) + - SERIAL3 -> UART1 (GPS1) + - SERIAL4 -> UART3 (GPS2) + - SERIAL5 -> UART8 (USER) TX only on pin, RX is tied to RCIN + - SERIAL6 -> UART4 (RS232) + - SERIAL7 -> USB2 (virtual port on same connector) + - SERIAL8 -> UART7 (DEBUG) + +The Telem1,Telem2 port has RTS/CTS pins, the other UARTs do not have RTS/CTS. + +## Connectors + +### TELEM1 ,TELEM2 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4CTS+3.3V
5RTS+3.3V
6GNDGND
+ +### GPS1/I2C4 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4SCL I2C4+3.3V (pullups)
5SDA I2C4+3.3V (pullups)
6SafetyButton+3.3V
7SafetyLED+3.3V
8--
9Buzzer+3.3V
10GNDGND
+ +### GPS2/I2C3 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4SCL I2C3+3.3V (pullups)
5SDA I2C3+3.3V (pullups)
6GNDGND
+ +### CAN1,CAN2 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2CAN_H+24V
3CAN_L+24V
4GNDGND
+ +### I2C1,I2C2 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2SCL+3.3 (pullups)
3SDA+3.3 (pullups)
4GNDGND
+ +### USB Ex + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC IN+5V
2D_minus+3.3V
3D_plus+3.3V
4GNDGND
+ +### RSSI + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2RSSIup to +3.3V
3UART8_TX (OUT)+3.3
4GNDGND
+ +### RS232 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4GNDGND
+ +### DEBUG + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4SWDIO+3.3V
5SWCLK+3.3V
6GNDGND
+ +### ADC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2ADC_3V3up to +3.3V
3ADC_6V6up to +6.6V
4GNDGND
+ +### POWER1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC IN+5V
2VCC IN+5V
3CURRENTup to +3.3V
4VOLTAGEup to +3.3V
5GNDGND
6GNDGND
+ +### POWER2(CAN1) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC IN+5V
2VCC IN+5V
3CAN1_H+24V
4CAN1_L+24V
5GNDGND
6GNDGND
+ +## RC Input + +RC input is configured on the RCIN pin, at one end of the servo rail. This pin supports all unidirectional RC protocols. For bi-directional protocols, such as CRSF/ELRS, UART8 can be set to protocol "23" and the reciever tied to RCIN (shared with UART8 RX) and UART8 TX. In this case, the RC_PROTOCOLS parameter should be set to the expected protocol type to avoid accidental erroneous detection by the RCIN path. + +## PWM Output + +The VUAV-V7pro supports up to 14 PWM outputs,support all PWM protocols. Outputs 1-12 support DShot. Outputs 1-8 support bi-directional Dshot. All 14 PWM outputs have GND on the top row, 5V on the middle row and signal on the bottom row. + +The 14 PWM outputs are in 4 groups: + + - PWM 1, 2, 3 and 4 in group1 + - PWM 5, 6, 7 and 8 in group2 + - PWM 9, 10, 11 and 12 in group3 + - PWM 13, 14 in group4 + +Channels within the same group need to use the same output rate. If any channel in a group uses DShot, then all channels in that group need to use DShot. + +## GPIOs + +All 14 PWM channels can be used for GPIO functions (relays, buttons, RPM etc). +The pin numbers for these PWM channels in ArduPilot are shown below: + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PWM ChannelsPinPWM ChannelsPin
PWM150PWM857
PWM251PWM958
PWM352PWM1059
PWM453PWM1160
PWM554PWM1261
PWM655PWM1362
PWM756PWM1463
+ +## Analog inputs + +The VUAV-V7pro flight controller has 5 Analog inputs + + - ADC Pin2-> Battery Current + - ADC Pin16 -> Battery Voltage + - ADC Pin19 -> ADC 3V3 Sense + - ADC Pin3 -> ADC 6V6 Sense + - ADC Pin9 -> RSSI voltage monitoring + +## Battery Monitor Configuration + +The board has voltage and current inputs sensor on the POWER1 ADC and POWER2 CAN connector. + +The correct battery setting parameters are: + +Enable Battery1 monitor: + - BATT_MONITOR 4 + - BATT_VOLT_PIN 16 + - BATT_CUR_PIN 2 + - BATT_VOLT_MULT 15.7 (may need adjustment if supplied monitor is not used) + - BATT_AMP_PERVLT 60.61 (may need adjustment if supplied monitor is not used) + +Enable Battery2 monitor (if used): + - BATT2_MONITOR 8 + +## Loading Firmware + +The VUAV-V7pro flight controller comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of \*.apj firmware files with any ArduPilot compatible ground station. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-interface.png b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-interface.png new file mode 100644 index 0000000000000000000000000000000000000000..ea342dee5dbc981235b8d9e5a6b67fca2d398615 GIT binary patch literal 56034 zcmeFaby$_n*C;%Il%z>XC<3CSO4n9IL1)S0<)N1-2acQ&#+(;BD5bC~Wfp{Rzan z7(LH!U8c4B&IBT3Jz<*&2$85+qke}c$-6T(O(|=5zPqHG-|t#0Ceiy9#d(8L$;UXV{NO4_mlzkEjgk$+LhwFqnjs!^njrr{nWi4idX>7#y1Ds*PI`07* z1@|;y%#pOvbJe|^4Ih+<(noSYm@IZqXeH<|3w9w81>>j>h!58jT&1BFj_|#CZ#!d{ zPhs}e7o1z0rh+;smiMrQ#{rIiRek>V2>TWzQV|k5ov1g>-=Y%}X`8}jeh6L-tB>*` z)_6_pYsgbe-r@bp&_5?;AFT=`OsgTo@b}TZ=Vj-7$~FDeb}vLXczcN=viO-Mn|A&X zJPjbIp+{~nmFY0C^ew_;S#nlS)>FhslC#wlsaws7qG`46s#McOXS$^l!;Qt?%j5jj z=7KH?#jXMsky4?^R9jC`I@u<)N~);p%1e6-2@HEldT&(TZ?{S>So+;$?!CFKCYOB3 zBc(XUUn=_Fqwbpa&otj0WHU(nYf$UaJ#4!X=6qN-$f05{icRh2?^O;tscoi9Z!NUN;^if=CNAd>6^8ytJnjk!=FxlUkz20f!O!^&|dUWNAQgQW0K zf~I#6G6lBubM`CstGt)d6aBU)phfp0>*`KhA|N|M|Jlv-B!A-6K>{j67f?-t^}I*p zY)dWUHOf3T`4;9|NLu%_u&wdeN1i_)CpNI^X{eq+y6oIgp6gaj&JK+z{@y_=aGD3v zhS=41WIGH^iV+l^`u#tv1eu&}4Gwn){#1aK62NyM*x4VcOfY(Q?qLZ-?8AGJGa*eZ z7P%QU1{%60x5U^`Iw+%nly_v^mX}n1d06!Ec?OH6%eT}U?0ViGJ|=-An!yyBTphhB zS9Wx|>ymu_?3Gl*S8A@lQnL{vPFuSN}wLWC=*wJS#%Ej^rQ_mm} z?J)>v)+Z1i<+kV~KkW5N@JBj;USAoEI)QJ(9MbaHrhA3e?nmf=ci#TRK{Q#^XgQa_ zjUGyf*sC|@%WouasFx`E8@I1{5)T@Cr=k-QXwj{OWS&)dd`kO6@yQ`4t2Cre#v`l)#<0kquvZ3WMhy>{qq%l~F-M{A zHt$)F?q?{N8=6!H*iE#4-AJ-G0msf0_2}jlDouHkU>3QDcQtK^(Qn*jSZZ zDZ6V?akQCC%xj+~`|jox$(No%1m~C%iXm?sxfP_=k-Gr9I%M0I<5#P#h-?ScO3e|t zx#Or}biH8}F-G)YoJ^_;F{;@2D1q`0JY~ZZt=<;94WB*X3yM{D2sJa|%m1VG_jy0I zM;@Rr|64&JGJD}(VZYrS36dZj?m?*wTiA`gDMj@ z(dfzI`<~!IRq_#dZMQwk*xIg&sw;b5x;=9TcLQ}4VdVF}feu23zYz;WhX3Zo?0F;I zioE6YuYT*$pc0j`XOwdro6MtTn;ujgh@wMCsE5|^K!Hfls`UM0QB0~E>kCFyss*l~ zmXS51cFm^w9TUopde0GA2Lhs-7incsfT3mx<2 zFYnW|61j`C<`JV(`D3%$aUgwQm`3vg;>O^QNTU`t-e%Szv7xZ`WAZ~(^Qan=Aez&8 z=2L5Sv771DW^Ja!=nleAd>$sJ`gp6vDf8wq2u7vcw`Fe#aebh9992Xg_YCHv&f9Wr zI+bM!4W;#&!C$<)CEFA8pVpwe6Z*HR z+M~nj*`8b0cJoF|qR1)8Y_!q{0q>`O^%E8Tci`klwlZfnBka0;sY zuAtc(tZsBgV{_&1?|o{9Qia#uhZh@UOLi!CJI}}!w`Q0l(>_6~%)s9`<#cZ^lb!o? z6KAI3a9iZ=C*K?bN4-Wxdv>Bj-Nd<#S=rwqHWYji1iqb}N?KSvftXCc8U2YqLeonp%i( zGu8n0FbD<}b(J|BEQkbwM;@qqfouvq|4xP+62-Y0egpTS@QkdMwef7_xS!IIWLCBa zjJ+f(MJGRH*RRx>yzGjNkum%9%xrVWyfRPyEyB2k{!Zch3jj~kxl*T^GXqws`)(!+N0^&=sgmdYmNq- zI%2`)ZIkH95)Pw0{^a+@Na9Bwk{-5W)_evl1t$wt-0u107^9kp7e%1)T`PtzY{~tB zCGTiru=fIqFWCM7YJ*{#vnU9BU=W$V4=_}U_iZh3-#uw8H2DKScF)>d^6#%42 zPQ~_Y^L53voSk2(jJU8DcMvY^MFHK;N0x-f-)To7b{p7hqg;fw7(6%@tjOFpx|qI$ zvR%C?so zi;n14NX`yF;b#yPdK^V&d55(X62E@(7cw>e^4`>yO!A}ZKlAo) zOgEs2b-&sJeP@|$vMp_cGtV5!<-CV<;!O5NDSpY8J<`zSdhrYDoD)V+6%Oi!kpXSl zjT0zU@u;X0#Fe9CD_hswO56vHk-0FHC~x9rovTrli1r$O8QdJ7f8p?LF;#GDS!i$J zJ&p4qrB&x@6xq*Y$JmvhgT`eiO$|C&Y!cDPVeTqw3#JBnZEfiUSVj3RHBB0Re~ZwJ zFtRtj?aIXK$MxuvFaNikBswuN<9}y>_rG;i;N?She2WgloGBjT!w*HsSX5xd$ITZU z>(z$Mz4W0r^QQz zJvSWP;EgMmwEt`CS)`SS&l?(n_4ck^m6wHv=nW`3BOPMv0XLxcv47_@=l|c%3jN!b z{LgGPgcS7rH}~!Du>YG$GPaxUYS$I~UI!>7GcWI!PA%eWX_KS5oK4E!s*V3}wEjw= zUi=Udb%c4aLjMxWf0wcTbvd2>U+houFP;79UzM@%|I*;b|6<6$%OPa{OH70e;4iBn zbin+TJA@AZ|J5p6B1kC#!V+_-Oo(wGmdC5q&<|i}{-ZuI(q%$Lz5Ok7jDSI=O$JCV zRnntO4nX>;Ibblq?LA#W_g_bxgl;-BK!vU(U)0%#z$xUnspljiw<8se0pS^hA;0GI zJ6|$_{(qbR-2E~ksP!{+y_%r#PphTL##e8$q+l{;Z0>*5F4m)CjR|K4C3+41QPZar zA-FgQZWMLfp=GelP?!?mh#{F1LS1~Q?Kf$OFf1q=o~*w2@EN2fGs@(6sg8mSCWm&uM|pG5WBSPO@juw0L(E$xT!Gtzw@U}eHlQMH^#ttAAg?^=DX@vwP4YF>6jvD0%$MiZ3mFV`E*47J_etQ^e`(eJ0@6FHG5_ z^83)k;F=n^C2*rjqyq~`Ya|$s!qXxZ3_Yd0WDUx@vwfj#AK1WYy~MmrB(7h9z9j^K zbAry2_@)H-t@MOUO&~yaM@??(wMVTA(B#FGDPM?Wg@DGO^cgm3hzf`_M|~r)dKbD| zNH@X_z8uE-Fn9`Ffbls3;d7jl0Ze>6M`Cq6$);CWjHtW#()t*!Z*JQo0Yw<*sT@QC z`;%1QMo>(Y1F$*{aA91}ZtcJBH}5!PcoN3O=028;gRz_r!?)7;NV4ssI=J|DT8!0Y zWNS5(BrSa*SC+`KP+*;b5(2h(4PkX<%TEMzX(yCZFPnbjt!kjU){x>$O|2bI+M?xp zBE2jsP3~46{p2eSImZgZwl3bVx7$&GPnH=pm0^ee`bA6j#(QSw4 ziq<}$k$qL7!&aX<#u6QnAk!v&3dd1_a6I_@`-R&=@IB$uDLce{%M z^l{#o!_nlMx586YUrNo0%FWa2t0RSj#*+wh|5k=3zGRqqJ3i|!wNiFM(GI6v@9xfQ zB2rCWL4*gVUT^|%ES)YtNSfF3j#`HVj`D+HE`vV^*er~nf3>413$AxT5Q$3ej{6tc zw;Be0R)h>JSKfw6*}<&z2q^_(C#J@qB{TrcSUL4ON~KTJFqk-rum((A?w>m;Y=KFAT$f2_i<>877?*#}h{av5Rn7*#kxDG&ByIXLW=s!j@O% z(_*F1X03BCbQ~BGL@?>GNfeL>Cp^+no>)Cxng$I74Tx64Z(4t%0JpyYy((@vU~b&2 z9Rm>1v9G`>#|PfI0irRmksay>fQ1W}yxjRl@0FNWP!B%rek@(5rSPVO8M)c3z z352a0ON5GOQ!%r+CpoApS(4Hv-_~Z^Fkl;z)aWj={R@N$JOHdr|N@jlpia8n~Xkd zkw}FJICIDkme1(5IU0QP29mnEfKr$B$Ym0DOT8}I#&YfZvh{6Za^5- zsekw_70EJ1qUI^C;b)2MvUHKskEvyk)$F;`0JKtiJ3#mVH}tBAN2I8?Y(eR4!^MpU zjKb7q>tgDHy)tiP-hajt0q+z_e#QZT^&)#{044^Z%=O3sPQRt;3cA)iVdWFRynXKSt;$Vd`ffOD+@n1X}==DZBl4Tp~Y1n?L+q0C?#X}3EtGOE^1SxEG zVKKdg`VO}9=TeHd@L@;0LUP%HAfP3AlI?+KJ!vp$Q4Yiw);c}2%ss}I8ND56H!d=< z_!RE^4|NIbVOt*RV3+#gm(%`qGOwqhS?s+dvWq*?RB(pc0=9H{kXnbx6@@rddCDfN zHp<%pKbSz0eR5)+m!pV95_|}a2&duonFCK>Dg(e=(?7oJwz8ohY^ATCLnPTgm8!6x zfs=YWAZ(HIA^9~)``zl)LN7DQyU69PF?5D$)f~RTbe^u}?6O?;7PsF6>4U!Okt@y&w6;~r%m=@A?NH;nv=Y{{6RqnXincyt9@7$#BF%*f?uIhX*!MeS=`ky| zciCCUj~-jzI8OSW;mfmFX`Ksn^bYkuQ_WILAYgzQMb(F(Mw%9l{tv}igPE9U11TBo z{yITZ0nJO&!8XL(Gfh=1aGnywf&wej-b(9QShL=8GuPIAP_;I%5-`PHp!SH(gP*3> zFLv5IeXS+$xH$d%OBV~tn`fGO->CR|R<=|;hfli>jpifA&(ZO_wYIP|HPr~udXD^Z zxBRg^N9>|{O73R45+%P4;vY+*5|Z+}`o5Q`uAQo5*F$;PLX$lCfGlJFovyKHG1>zM zh(q-YMFsT2&a_t~@|La@KKxbT_=~%dPS55UVl(H^s)Ue8->KZGcGZEW>Gke}=kEot z@^rC`UU1*JOC_pKnq+Ra?q1$ivQRkitLb#j`h#kZY9u2UyvO$Hs&8iROACHkQ1i}E zO17%^h7rbGAS{@+r|kaF1V34Tg=qfkoi#){$Asz z%f2_#+FY^&_A$?G4OI`8I+$oU&^7w4O9?&DJZqt)Fd^;BV|O|u=lW8~2?pBb74bq% zXsZ7R^ne%_d#H}oeTU3mGyh3n`4C#2Z^t9TWJ#WFl+C0&P{vsy`s6^op59MMt1w(-yx+>w<7u5Q@P`gZxzgv?x{1H&KL zpwSi)h=>uwAL>)q(5@e=4WXj_R5zeGFwR8j0di7z7r$7%!RpCTdT2_y)cD&r#MiXL z?39iuERgi8v!a1Bm=>QS?H7B#kv*MrDLs6_1m4E^YlzLmxQI@e^U~qH*9(bib06MU z;A;GgJtsdJ0QDqKrB8o^LDp@x3(fK;Xl=R=359%6jrxX)^ z4bIGiFPc3;tJoNRb)R$he$0kAjzqbQZD;!0N0w~K*%c4expqa!sW+(khRrcq2_veU z4~@wzotsM%0^fxW>`$ufiTvbFQoN$%=GY`gAsAAG+&0>q+WzW=v+C2wQ$vRyD1WC4 zJXNSne4NkVLrU?(dpH<*?4G(YwG^N&oU_S#7bTu~}>Y0it`eGL_R)5JR>^w~zs z7kg-yhUmidnwmKvpBp}0)ZhM*DW`C-&YC)Kn>#etQ7cB(eL&P(Z$;7ziAy zmPu&Pt5B(14A?k$=?cr-Sh_LF(VC?^k}gZom6b2pbnU^H6!XM_1M^ zRd*y*wC{j>I;E|(B%{CaLJ-^JFBn&jqbRPt{J+i!bnIyFCrfksaHi0xm$^rEMk29c z=QJ<-)`NHGN8i|dD8hsuZ0_O1`X_|2+xx!{@aPWBznu9j>qB|CAMQ)5qlE(q(DwS# zRThc1yXKYUQc*rG-Wofs^1n?Yt#_&M$4xiMyIjP_sK{Z!m^8!#$7`1f)ynr~XNh_3 z+})ItcrY*gTh0~=Jdzr{d~j!Xl^Ne}&!G3bE_5L72_Zat`fcTjeDUc{+54ViW0vF- zLn{sH64AG0#6LvMZEdC(%z zy-%|7wUi7XuDdBH06Blq)4C-L8y@=l)lDysgID_oHdD8B1-;L*CK~HFpWhM*y4Ouj zioX@M`RhYRMHxH-^B7SGAhn};d4{*)bl*)0!PhOdAh_-(+zlGgv<=7GZBOCY@mEc* z)ulZvJk6E&1ErT1Y|eih)Qn*fyRv#T>4wyA4Alps6p?zqBL+I0^%n4Gye=|3Uc-S| zge~!Q9r@6rU6qUCVYZYb%H~g;NU-ajCT9zi>lkcmIXB}3;UPkZ6l0SntPK`fah_E; zpP9y@(OX?50ZaTx0}6I7#7c{F$&qNBb)SyQXDeim+Y%UesECn8um7c?cXsk>6P%_W zoEM-DA1&lw4SS79A;6;*a6q+2rtfII(yT4?d#t*r>u${wNBC-bD9?ns5B<1!#<{+($Tc-Bd{Bld> z;W`>Ls-kXqj5^1(`8hMt8{?N_K3%OfDyDiUs)HR~wiAui-F_$WB(7ConK_nnYSW6i zac+ReCSFhaMX~rMRVpl)1RccS;5gl@&M0)+oxO9_0(`H#15bfLZ{cDDN2C-jadb-W zwTj4j!1>Iib~!s3QGkYW80pQ-o`9NYOV5D^gQM9EX~G_11M8dHuS6Qjj&URnobibx zx$_l+7ecuTQ`QmvFSu7>QVa*6+fGyXYr}umQRT?TFlRw2bbCmZ&T`iduRNxmDiu z_`6~S*yy7eFu9o%i>rqHaavLP5pwbGIc%0e3+)!0VdExU+oIQ|Nbz2a%1hZ{>&V50 zSk#yO@QkYMy)K^|XN$(01gXm|o5QgQ)<4~_Zv@9TM?L&R4Mmuc+XHSd(U?QMgv6PP z={fg!>+zoYk)||uNiOFmaHRev@1mD$FuXdLLtRvcpNqT^2Z4S5d#a$Az_4>Zr-s#% z;eLWUf}X{nw;i$qfM;%?_x*T6aZH==b**hM_N**LT?pVIxSC$30oX_N3wkn z4&6W&dbQzNaQ1cWbK&e=x_-J1i!Gi+^bSp15|0c+A)w4qgG>9`{k&z;%wy>Y)${9 z$=dHwZvV=D%TlXHr_1ZQ`Gbg1G_ZjjfjC+u<*!;bs+SYLIaE74JqoGR{)LWg{x2pr zrqfSJ==Fbed|VSY6zQt(%SN=<8&ogeA7Z%}R}_~qOjpc$g8I#vzDF@e%_~KDcR5 zn$Meduc&Qih@N%oG7(|RcAIiD+DVk@5>T~W+&J#J@-!>*Bnt^2>i4A+uLLmve=S31sL``YA zcGnV|55u4tMEZvMeVQa*UmV;j9oP(C$mnW?c)?nMcg1}`6n z(b!9fW}a_!rJL;}mka$oM-P&|Js7`pR7%o=#crRmDV*8G?0L?iZi%sxghuaYVSJwm z&t(*k93zIbrg(MV`Zo`FI;(-li~pXOT@2q6lP_BUfscG%&tmxRJk+yXN3(6 z@HF2TZ%-kcn30zy=M?HPAikbFJAsclOcutRi8i0+}&+_S`8xt zY4E^*lwl0h((wMASA0@KPC`;Jg`O0GuJv_QO~iA^LNlCt+_U$bbJ4+gRs<#J- z9=}T$$`BP)#{@O&G>u&zHB4bT3|Va;mHm3uY@d>7;T`{`#}jc}d~} zPxd0)GdhVSaVpyN^-g`4QFsvay&h`n@)YJ*8tkT7^tbe5JEHSrS#i@pDS_#sq*5d? zj{SnB2P=|oh-3Qjr;gA&65)T5K7EY%(s~0Z`3mlk44#wc@gT$A>6>+}#U)>cS0J2} zf|8(+^{El_-Lb$04v~m6sex0kHJ^pPIaVmnp4g=!KK{`)(H^<;j1fj7gFvNwC#6rb zV0zAh(K_?62d_F_zh5NrQ60XOSm7!cw7#u70Z-nDmKf8%rdx2U;TA%(FKj9b%8A`= z1l_q?7LKokU0_n;QJ)q6+sl1&GJF0m&lTRLcUpCMM02&*f|2{)SoBi}qYGV|C)Cbb z+>fQ(I1LP7_HNXpgBRKpmfc^shCT;6YJ%$xwF^!LJKm*IeIHM3r#HJjA%bavtw0G? zC`tJFMf-*zXl%b&zW{RrRu$>NS+R^SHmDqhf;oq+4>^weK)XTg(|54k!IdxQ$3_HC zeORlzxpC3a)^6rgAIYbV>;tdARyHv!Q6oC54B=`FW0#b=)|$oQ?pA)}$^cDMOl@g_ zS9m=o*vM*^4@74~zg{WGNvB-WU9q0lb0-w89d2cFDp48aQv2E44pk@8&5>{5EKtz3 z(zddJ?Aem^E{De^YuX)Y>$P(;(whDIFx?7IF67yHnYtmUqR>!I-Z!>XenXA!$N9zB zyoKqw+)DT9Z*l7rCaI+0dTBP-g&)IkZXJ9@ort)Gucv!&Hrtw?k6g;@*BPCT`OJ{} zct?-nWbo?yM`T#rNGC-GYk0t(JH4hR9(_9MA0fquz0vfWVJBKGWw=Gd;2K`LcsHNysXEWn;e%HCxG)AFd1ytqboVvB`_Ot4fc}a(#iGwi9`fpQ>WG; zer8d#mM#4QlG-{$eqo_XvczcJ7Ki>}L2RKky*_Ugcw!;zGdw&~v9I9OifwmZE}6$P zukN`yxs@54nj5c-87!JidUpBSB^?@z}yNjq}hnlGKlr2U(Ajl7O4p=M>xPpdJh7yb_En= z%Atq(W!?jY2D6tuxh1=a1}o9WPx`(af4dJFFBb*r1%v`7H+{va0CS5G3|{#-Ef z08i3q*%jiOpWVoZkq{C^u{?F}#c)|UgXv3nKFIHjLN}&8P!Dj0aH0mBMW;D6Z2ilE zNf2%U;0iYq8_mi07AW(KD^Nf9+wMvpAHHa$B#ySXh}Eg%?8<%k?3z{~F*Mt_@2 z+0G66p31gPhHQsEgBU>`$Za;!6q$(+mjdCO3 z+AeHneHDRwP98$mg9_`73my&Tc59p4CDAQ8@rZ~YLJ@bn5PC+B7GyER?BKP(mwc z44y6)-LY((*}(?$*45Uv&F<3vv`1pQg%4h3sb$%InILX_Usf_}UV608&bFZQGT9AD zTMhVduzLGo<}$k9|GlB#j+xTj`l3Sh(|)p=Elwg5upRn-pt+%>C?V$*eCmIIEsZVB z!>ZSqL_)Mb2)9L3?{+dWjrI1)fhDOm_hGt;javv!_jp7$PQPl+IGo3>p7X)8Vop+U zGRR4w1QSst>a+x>oHn6eD2VXXoCisLhsM3| zyd=N`IS#D5O@=JLUY%UwaGJZ_!>a(_Bizt%1V_Vv>U?-GQy(!VC3ei5;n4b7`=8>b z0Ox>^8>73Dd#Lr)Q~QIU)|%;H_s`e1ml+tkn2qMr%(z2ch&Z&&4|mjjZK!M%?hkkP z2{3IaaV(AXIFGA_rz!QWQiE#)>#Mj&N8B8)f8HRvo~3+s%;K)31G0)MvWiePm$LJk zVRay%rdt_<9prF7d&d4`e8YW6(`9P{4^W%&}9> z>juu_X{WmRh_J6|Z-iC{l88ne!hY~bI;bCt;ZbG!NDY=05bf2jBha_H99ej#zhSq> z>jnqpRz5xUuDTG+UFErzLUM5I2ZCS-dLoq>hJ}$!Jq+aw@;cS0)IjeC@XVfi5fpSlXAAuJ>$Ywj%HRlvaSHSZjn*`$BbU>j$Qh7rxe$Nj%8#3pGSfH z@T2lf+r6EUW%E+GNg~oc(xV3qviWo6Uu~Ya=c?Fh6IT?RSr^$?XikEW5;Z*b@Qq6Y zjsmOdnPNY+w7SZ$V=zmm$^;m(h;F-n$??)Xf9vLcj|RKqfNlP_B6mk-XhE>^8*}}p z9iOhL(o4COjQLE=M00n{4>!{!3rZd1OfG%8bvEaS4SM=}JjQEY-KiU0dsAFQKcG4` zm7fMAdVWchv)Sz+-DrI=F=YK-6G%>c{64CpANuB`$Tx^~B&dqHdSGe1&C#$jnH5Mf zt7gq%Ny!+A6YNFp)gQ||yG%TyFp z1O^S)> z(Ca0GlAiqRnkNZ4jycD&7qHhH#B&WQs^Exv#`fYI3|{ zj7ZFnNM`4`Ek6Yf7{iK4|Z04^;^94Nc<={ymw$%O3XNQ4LW%k9OSR(1lm)TA4H% z9m7cx+Bd-Ur1#n+F>&whZu*3j4A7$5M;XyR;`i6?u1p%H$gz`2t(3l9umAP|cY&aP3y*o~e%HwYx19r^oTn%X$+s%?i>hx1e{6bWTO!&b|#q0BeUFMRrwERJse-wLT zdf}n*I-7_!o1T}5<}wTG4(Hd6u{mQ{$op(^;2ED~OLpq7s><&Tpux_?;;?yQk*VvQZg7Uqu7V4V-83i`%#T{^%u!(9n6%FfRwqTgdW%9IMZ?s zlb|9&GDe)uVLwsmEKXEX=5hyB5AJVPe|r{EMPm;kRpiX;c%ryu%6=KQEcRm2=S(Le z2!L|%dFXi-{I8&UeOK7baCGd^_A857i`uY&y$*)PQJ)ENoUx0ru|0p)@*!jvmTdVC ze|itDnP#qJlG(?tXmSI**_wt&r-jb5e-yUSm9`u8_MN4*TW!kV87;B{*;fAg8(3Q` z(IuS^IzNq@{Z1VP1nVh{nWn5LKI9;se?T54zEUR#CR?K4;&LqC%YgkAjM$Z%$Hyo} zzRrb60m_?eQ#}C^y#LspjYD!V^|JG?Hjy(jGU|UOzL7fQ8_+~@Wyb$7F=XO+AEaCe zSMEUNixrly#Ddi9)|q?eqTi((b~9{m8q|Y-UdNm? ztf^h>I6E|Flw9h3lc$6+GyLUn91$+&z#CO2EL*v`T|MRoa2Zyw^&_sx**_6e5GS=9E(6fA7TTkgFjbOe3M3 z;dmdNeWKl(QttX!wVxGO>?UOvvQeKR2e0k7%)+TKo6fi36`8hf?gNd3C#BC$z4W?p zL4pn@fKd*&^R{vN&V!X2moqd*cjs;QBZB{SaxJCj6$wK}srl?cFcZL4&SQDZV5TXm zg3eG#N{PW9x?DKVNmK^uhGQ&za*W5}UJcllH_YVl*UluLCwRVfW@=6>nu&%iB zqUO*w(v@j2L=WMlOTlUZahtVH!(n~#UNN(O5k*Ee{)^wL=b z@?RenvduiZKr$4Qg zVqTqGSC?E#z8uwXv?a!0dH*T!WR@yBhuKlH`29jd;@VPl7zv07&@(5upad{)CQ0A% zlhW9?3;C;zxv+SOYZn%dkb?ZqIbEtnJ8$9LGVr^8NezfDV@R!XZ8|d`CuYF;=Pma$+KslS<^osbF~UIs2wK(;c0pg zgeE{*1rLx@te2z(FQKjAInI?G^gVJz73K<@7c)EC%2Q+g&Pr$QPx|$o0N0I~@uEYg86n||ThW?x)G)_G8ThV0Y6<@>+;1u!L@2h*n#LIbej@PLNi2`>XfD*Lc9gVw`7#YZD{swQ|K_a?a` zo|p)yeKdgV^($Cq%QgpATl{o@)HNfHw8rY*WYfd^{v4f}N%f!VzpGogYb8?^PgCDj zhW-Y@Vdi38a%Kzn_|B>Dxha;mlBYD+Gc(1l?V>FM_-Sc`=wNZvtCcx&P6pb{+ibV! zV~ZZgrHbNNcNPwHyM|9Z;q6s9Zpbk8;rY3eDErd)E6%}>7J4Gc!By%}5PL1WB9@w1 zXdSOxNiGEYYp)$F$)P<7|1jsyvVMCjR_VLgol1bQqE^Ko{qRW6r=uo%_qHB8M(XXx zg`irZ4K9cp036d5Bnn_iP4&s&nJO{4J3mviSYWg&_mNU?GSus7>5Ip4ZDND|P_09# z{l|}M}^CR)L%%Ht-VroMA^YtT5eL-|FaGelUjY7B|z|loPJ~_2CTGS8YGTQ7B-;YAP3sZX~kri7nhDcJaSeFCy?}*w|9J#+7>? zl>Wpr2vTXhK9lc9g4w1`SrX7|B(aEtc!s}Ty?*3iPqG|2F1v$@WxdR<2+*kse@TXe z`M~`Q-IsoVq))1)gUnJG21u;koXigHoHKjXRCDA!!zM_sYcShQGmZ@K=lkwrAEU^a zO$>%utrb<>XsTeH`wYsC;MmedL5lv+yJhCNA?t^QCd+J->NSBGe1^*QcZe~9gG1YS z10H38JgiJedgm~dvA}3&Sb>v;d5^!U5xMnNc$fC6oG{0&FWuxiP z0^oWGw2LUpB%nC9*fn!0wsG0|RstmbvUs*|^O(m3af zIg-7?&s$e=!MEzglZ(Y7TgK*VPv5W$6Fi^Vz~~~n&DS4LerwDj<$X@TEBG%Nxz#LZ zwLu>v#t?%9Xn#WAs-(Z25;J*GO*W?gls5i-2=xT@^ye5axjz52dqdwWZRR7kSy)Cm zL^BR&*--#Y&3jTU4x)*Mkh)O7eayx1{7yqq3sDQ{S>!x3Cjg_Fw`Q?$7N-&;MLACtAz9L25KLeUJ%+Zp$eEq2mk@ zfbem+DVi-T#PaJ!!uomRoQbSnQwK64z+jS4C{HR(i#?cp1`IlIl3@cNLHJ+-UHy5X z=kY%9U5}1_!;Tg!_lN!Z8VUW;8(L;c1&qMr0XL)ELac+;$qu=@~#(-PT25h$H|RBfR9CnQs1e= z`0Nzk)*t>-dp71p;?jEQlj$>`=GS6WJx@VC6wnKL5_AX{-1DWX!!>lS8{bdpKE^Tp zq1%659MB_4Vywg07j?@Ujyl{Xi;6FEBPj9(68RKj^ls7a>a2OX@_vS=ah6mC1P_A_ z<*<^d)gv1Pj@hidV&qryd2?^n&;U{BpdjONimA=JHx*lGP(_<+5m36dudPs@5b__3 z9AR9?xyNr_pWJGF0L{l?3lVIw$wQY$G9u2KU!#=cOL5VCtiAht?Y0{vtGHK|=lZ^(2$?C8 zM6v+bbA%N0+wYHqA76qj@n8xj;QO3MMd`Q|Y#TQ77tP`|EDjcT+{mZYiTOhrUx+dn z5x*8A8eP-9|76D3vH3ZrbrQVW&tM}cOwqC35=(Y|M=o&d&&jf6cLO7N#G-?DZ+{%j zjD`FSjD*XAQ;WKX-}IGy3Cz#BkO`k-fC7#6>@g`~8Q~dxq{UmTrjS9s?xdm|rwOaXtAj{7yL}Bf@Zf6^fL+v%ME;+7! z-JzDycQS4jQrW=gf^@XJG8ovAvYY1U>ylPXLXt+e0+TFNVX+r9Sv`K-G5tondq2~ zW3h+47dZ^jZHnY;jjSlU6UuGB+laYyOT>EJkQTHou(z65J>x};lY-%}&_zz@2R?oK zP0cao9UPLJ8h^qrdJ1;Lz-=^y#?WlO zmI87%Y|-}Hiyx|s3j?(_9#1liiFl+U_h?`@1A;zQSkIy#@cgdq37Ch4$5RfL7t(1x z)je`B^KjM=79sgQh8)L^N;-XN1yQ?&uN`7vC$b9Z=;Dy5lmpF~8l91NkZ;YE$8_^M zU7%IZN;S(`eqd;k>iT}%c|b!j?sIOv67tI}CGNylzxlgQa@(y?g$96(O(eyQ4Qf4d ztlT+8xmvx0@4!l?*el$*kx+;&{`A=SEE%kee& z!6<~wAnADhPvFlZ+F=`(rZkwVJ5&h9g@#StgVH{XH1*(if8PhDfcN5I8d_PmrNfbX z#{z*`>@tsPKM~%ans1odIx5nDk{r5q;^qyrw#6p}WYR9mVwF@?%$pgK~dD~tHDGSi#2+(i!#?@Rf@3;BctQt+VH{{2D^{TXXty0@azl* zRs4%$V!39f>1IL}g9fG$K531vtWJN&a7%nbB=^v(*%UH~PfC}r!!Wl3WBq!jmK6H% zEM{=yb_T2W@xHYD(#MRS1SBJ?XrW}=u!X+%LDe)Hi-#r;-PU`+pb{LL|D<{dX6@^e;eGEds0bgkKAG1MTE|Vj-){>aywQ1t{a{ zQrZEw5GQ2WUC#7&u4uSPqg8G9+WW|ZdaK?bUTAyzO31>;+tl~qZP*XgoZM~o z&&i)zr=j1|v(mL&JTI8d@?{cRJQ;%BSTeuvoQ!2DGTCDs0SAPkd$8&lg5+kN{xhE4 zulT$6*Lw()LDbNw!ecylhDb&Vz^g+tC++!9zYzzzX5 zd+i>XesrCQf=b#v@X>M0_w$WU@D$$i#E|^T#D`Z$B6p!z+1Q2TM%a2U<$|)9J(Koq z<5Sf?i#~nrZ%ejk*~m?wBZf9-E~I96o8+@Hz2^DWsBuR?QAiuG@<~M&p9&&akq2tn z)%Ce1czC2M>29AA1BmzvhMVUoebht@TuX6DkImYoI*q^@0;;+CG5mntn zW>5%!-^$~#CU=(?#oYYq-OZ&@QdSPoOQ>;J%$_%z6myuFh9C|>nrUZ4J5Da`dQ}09 z@qlaEvgZpq$iV}{2r+C0+Ug~^5fMb0m@JFJv5cUfNeQGlNMo?b{sFM-nU8VDkV!Rd z#BzLrOi$83>bUSGcJdq z-0=rc4s5`HAHGus*?qOrAFDsl6c-n(yU&#sp8*R>EfSn8k|IT!42#lwG4vU%42~?Jqx_DI$lFC%7eEjP%a?TF3fPyJ7 zla7f(h6GoX-zq7w%=;(lHBt&}<={>QVt+Tqn@2p4p}7S<|66I&aAt(K zB@56}PDq@LS3inxpogS*Vqd<0Fg+DznYJ&xrbyC4(`XMt{DfP(DgWq`I;@dGjaD5h z2HN*b4=lE$B4%LEWma-Xdf&eVclN+PAo#}GTK2@r;sNuwsnq{fwk;z#?Ld80yyRYn zBu)CzX1ZeQj2pZSkaqen)S4jT0#Ee#K1;2v?t$Xs^{s##u4}BoXX262l<~8Fpz+#n z>!8{85N72QVy#{KG%^R!NE89?MNI8Nhr0DG0CVhMk|}cdp}9VPM(r&;1^e(k3L@1| zo%5;L0lrKf$$`9ER#dD&6HbkTT8u;&El;um4kqz0I0BVtn~SOWpjVISFSnP7^Hk5R z<Q@MAvY`X(WzaDTd+y@Pr=}w z<^cQr<_5?{d@s4hPnC&_I_u2HD0ER!bTToMeBXtNyuEhTBdT+K*qo&(euO4p4GbCw zO*(rebPIZr5%wI+ZF@pc8Y*+A9ph%&xESDGq;P4kw{LKCq@N2EIopsrlmMK$IBkwY zu%rb(IaEHD6JFeO&B;Xw7WlG+5+0#dF!cw#Ls%umImJ&SSD%13=TV{WDSs%}s?aUS z^Ya4^r59esYql3bN$3UK_=<^{kj8*f-pbQ^A1Wm5Xiwt2OK-+>tO~2vZeJeFoa5x& zqn7Fjh{>c600bI5upJX8e#IWY`Z=I1xxSfqfu}ya_|)hj*5K9TCzfk-dtx;W9EZE6 z6o&_eL=SDz>u+EoF_Xa%G6CKC91q}J^}ggAgel77(i$Mu9-K;r#9)-Ucv|;O_@2mn z9&_%cz86HleNTau-rt5l+vwa3*@^yCa|_>*#7Iu~iO7xCF5p zE_;z`Pf$IJAwqn_9AEzoEvvQjDi#i}2UU&Gj=LV-6)xs|=+tt8NS4lqId8gIed} zQc@i!gCH9kua@J`IuJjh{$=Mn?Mc>j?ytQanKw0z=K1`-gLphqL0o_&2!SJGbW>*b z$4@_p_?mNTfyU21>WeXaNf00OEGkVrqV`tVQ+?*tlr3_SmLwWuuWGpTXX5k8o748!u%KVR@e`p z0$>VT`OTX7d67O>qF2}q;E~f}o_s-8eB$QkGx4w(oFPVY^c6sXPF_`FJU3v-RYPNP zoX*!m1I5)>@$KFd@wDm%4&pVBX*Z0H>Oc_c3$U>3chVEv7O#4AQ{q+XZBWnh>G#)2 zaAJMYOeX_a*dYTXvCiUGr05qVgj?vggy`f1~!yR zRl-f_5~K$Oee!p!pv!U{tZpldItjuvfF!~i8Z~=Xb{#)Ny@C;Yke)F+XgpjY4)@y( z(q7cu-MG1air%>|wHUj7e%qzr&-&*dMJ=ikGl{C*=)#WdvOJ~bBgsy3{Y^SSEO;>& zV_C1Y5O3EA3%}V2;&}wNCcL^@qw^nH*421MZ+d_bGyE^7o_tUr`PR<)t0Mxdo1Mx6 zT4Y`!rnhI~4qMoXWoZVMkH*Ct-^V@8Do7x*hfr7Fou4F#roi9v>zXh{OvKLOydqc; zwhyVo&31RY{``?lyy5H{EMruElPP`g45*OAhGtMwx80yAm*n!t3cKBeVF;$BAAa#z)q=qK)9KxlIi}V4#Sl>l4>TxxB#0wA#8CMY$T! z*ToW-k-5}bm1BLczjhxYr`29;(*4cRH+lg2%|N8RNQChQg1~Rs(`ELpTa8hvr@hwn zXuFzMPH9Q9>QB3)lUQJo7QKmL^y(yt6}WILT@W0%ajw7;W?&;JyMJSIZIh!oDM=m zQ7>6c*Nkq?lzCK~5B6+O@xa{ZoS3t!e9(q0Fho@iP8*w)HbV28%UbmB0ovVrgRn9= zt^!?4`;l@=4u0-A(<4o@;v|s~u31m{0I_=6O?~P$aw6hHHBkD3$N8nj%xSB{;vWOM~n?4{ryP0LEcY785x!ztpju8EaQ#S4tB1G_mtimLCa$ZD1s*{oP&D zUt@t|!il0-)r0ToG44)Zq9c`p^~KAbU*(PZrXST1WlczB-r?LEBR8nBO0?dQFIV|V z#OA$+=rXjQgx_uBQqPje&nj{>uT@@GNX4?cR;*w-S-IYerl#6!5kXZ#F~k^Ek?&=@ z7v@gx{rOU|xy709-KCULsJ?Ap=eJ}bJ4ODT;h1=@Y6^+XPw!}5thy-W-OPHT$@n6g z+}J7aFI{R;*y7-yy%3%P*(StrZQUKyA$IUwxk+o@lp6~o9NFxMb3g`J*_WD3m7U%_ zjAWi!JFF>k;ll{mLT>xo25)m;?LxP+{Z9FZM->OnMQL6#_n990;d0XN2T9C709WKb zugS)DwD!rhl_+~WJVj1l)p_`Q#=BI$IOfd$EssQOc3!tWBsB|sH^!=TrxWXaWx8wq zqra8@w5*Djo#M%Of5ItuyIbw1V5Y)vv{OA0K|Q1`BpLZLmO2yz|hoKBl|gAam81Hsw+rrErdv{9yKt z7aO&CuSAXwC7mT=8;ZNm6Ohm>qE96YewJ4WYm4^Q2br(9l7_D34V?z(z>y|2P; zk0rzKN__TPxeZ!sD1MB2XyvLt$>%T8Hdr=3=<@2YxRrL}mI9H_VPuPhX%SAiNA=?n zE%#;5v^GlK#yM`;K64(RMr6A?=RCExz;nyhGE-tXXl+y!2RBa*6lWOA*9+bwV>|N9 z*^c$YsUN?7r63Lcd`b*#dgP}lq$Hhu)BnRk1)nU&wzx3nNSI=J5x+$df!_1N=q$E zELR;1JfoBGlr+v3Kyjd&CrJcVQ`W_$IO$spLZPMwN^aEmY!aI1?H;;mT@Pl0-phi1 zUgHcX3$5j7IKo5`o-p&X-q-bb)n>7|2Xmz;+~3x_$KFZiKt6Ow%PRKL&NRkoER#w) zQD*BvY_6Ir$pfv|NG|uk&bX)l#F}R4%N8RK@HvKHN8}T->%)zQwSwgxI_RXREjlYWU$^Vl7socph&r0?E0DC68I53m<)j)hz$$fan= zF_dR~1lEWler4~@_TP)aJsljc+?z#%JhNjrw-{4<`!$TZGjBkYKuFP+np)=EdT5lE zsWEV=f^48o`|j05=^u>|~Qo@D->IzV65CCNoh1JTgtK{57L z4b?;LVbR|f71}68e-x*ls!ev)Ey`^kpFIraqMNmNJ}a&*&fbE(=R*w?8-Z?kTr$bp z=5-e6vK0hXsBj&8#B2G;v~bvJYEGs9`)~?#+dzlIh>G>w*|LpD{Tg6D1}maBoS{E5 zls}(hOL#B&s+{*$hPsEuEMKBDRQ{wYct9>##>&%6>@4Rf4P>9sr5IlQD3r^u1~}`8 zW!Q+MjWSjQb=+m)q~M}4mt9%of0nDPX(ZBH`=YXD`2fM$9h3g9!h#4|7oPpd3&m)) z-7nxDDm}NlQlnZmIsK5a-*lJ$gMEdeNQuQ*_Yfnc-y%;TiU!E0BTCD)Xw@$HqyFNX+u3Y2!4j79cyF zKqw{HixowVoE5l6$zT9&PIk+5D^0i*HkTLkr}&R#f+?FU>^0(U+QIhmo+DzT2W4^u zd6TeNS|0M9idc@Mgifntn~zxTA0uW9@)Cojg5L&3O${0hi^!w}r-8j%3=DnPH%W1cN?lgoi)LZX24bcYI;aoI%!P4d&y4lSQm7n2_h_|tK`q)=2Ea`eN$B^^`w(D=~#-fsqWM?gLUXJXC4uQRS}L+UGKNe zWL5_2LrbM0v&ALJZU^h=ZMIig%N(2CygisuRwor=vq@5ZOFf(Pxt2jhfg5;9AxlWUwGTMeT8O) zAusJp`ai&qCzdg4@OivQlY!!4&&2r?c?<`S?cAs}r_`AEfh|}r`c+EDU%^;5NP3ryQ&Ud)mEBdQ z^mIKp-K_%4Z2N*z%Q-^iSd8B1HuFe`%^TK~olXdwqFc!BDwTIN%Pi8vn*R1RGcDC2 z>KD(U2oFq=HUvExx(xTE`EttWMr&JCr-gmuv^Ve#(4elUmocaz$D||xU+^3+w}M6% zx;?#IMb*Ksd-}TXr6-0dL!zFX5DI#8-dsX8m;b%-aqS6a<#i!_za|b<^7?TDX#B%5 zz+KdXjYYyUt)K3WF3Fpj+8PH?o@?(b;nEnj{c$hTFP4%<-NREj2TEN&Gb8r11kh=1 zD-jpSbGmym<-)dgO#$a_n2Vnm6}5g>$P_Tx{jLBCEo$ysL6svc%^3q{T}j8iM2$ZG z(i6?`dHC6APW~8U4keAX1<@t@bMeu5r7?FBsPW~T?^PnG^t;*Hf24(sY4;p*&sm)T z2fhN8H+YzUgVMb)xTp6VZjZF*!n`ishe(LB+CRl|XM9xova|Z$O zBaC%jSq&jtI|X@s(~C_hW1sZ5j3#At!^yMj&jaTD@Eg+S)6Y%v+j~;NxzBu6GqeZ@ zyGaf`JTY7a&gaT?s5naJY0_|K5AX|$Nx8W^QmHrv{AppOs@f2#sJb5GIzjZCk7L;D zO0(bm<@s8E`5^G}rFk5e=KyVHu0D--$|#$oPA$HeJ+;$atzq9Q!;H}*Le2zf&u@hG zc%AP-C7;@jlp~xACozhWe#Ez2X>sLQ3fz!^T|xG?4A6}J8QWD%VL3auHk1dXzc`?w z!jP1nq~-o54N(t}=44YsB;FgoN1)KctTg%-YwcTx#@rB&3&^$p5`8Z$|A}1J$nR+D zBS_RSYnm}3B^VM)3@sH*x5op)(t#lVy3UK|7&xH|mG8>I>lyil)nfJYF72*l1p3F8 zaITPVSb2JiuB|m;cSG;&Z^&SvIg-mII11DgGquqtyUc*;1rko^i+3Zhw%%XRRIVZ? zXP+yNmfsp0%<9u#mn*33+F}G()?8sQ!#6e()R>90BGBi<*lR^g1)|)gG1D)x$%t8C_>`0%m)5H&LsI zj})#HR+Qk}J5)Jr*r_w%GkAK}=>(H_$2MJyKd4&$CIU4=$Q%mIo9%YiU2eo1m|_l( zrJFw@f_xM`Txm_fDX-Hl6}85}^z@Niy>}!-T#+-Dh&QT?-BfTh^@o@bl)p-przO0J ziRu-8kG${S1Fpx1ug6wN8k|RZ!2o)3SxAwMIY;WGdigB&!XY5^IOr$xSEl}n5b(Jg z0IRkz(_n_cPwt~tO?T+B{+wI8H*ngZxBzefIK!cd6KJAxF>9B{Mid=LftID=jYCp) z`p0Osn#bRZqHHWJfK*mh0-C-R>iODOQp?2P2LfUjSmZr4<&soK_l!pk?5p0mbX}s< zj+cj^OLEsIVO#+=5yX5}U-kA24eunb_j~HKPhEXNUJvb;n;BqZLjVpflc0x1BGvqbx9?fyWg)3LcOM3ExL6vXA=+}rN6!pC z9^=&)%6pTxzX#)Q*r}tF1dhMG4mYZ;Au)0Y!;&uzY)Wt`fPLChUdH)P&RviY5sl^^B6hRJ13`lLbv{HlG%EQ+zSE)p@ z9-Hm&S+}@ko|NX4IxU^Vu#W(}pbg@!B6S8J!-?MWqg9HgdO`ae)lh-tO#9|1OjE*; zqo~K1%#=FYUql&Wkd$BF&SfVeXonU$1pxB<<+>k>xw8miU)gI~m!u!vuG$a4(CME&mDSop zN6gpF67JQaqWi5Upx;=qQTp{@?_eV=n*o9!TAQ9MET?``Q;O$Bq{dNdOxR96$E%2y zBe}LT;F1WFw-cW)vO_^**wh9oB7zHml-}04=(XEPWyivFiPf&~yy?}A{Bld-^Wz9W znqrpU1MBhn-gIA|)uPZBPoY zhFArkg<`3Gsa8rdU4heMt|=gMJX&`=qc)n8bt--`%fycF>q1w}wXI3a@4@xq9>sep zikAHrAt%8O9DbzGKtbi z?mn!hGlZ%N!*bp=?XonmWe9Y$?qS6nx;3&*$K>BVp~b(XnF*?tRBIcc@s4DHOLDG* z`Sfe9ismN895tfGEcJghadrCRLW3h^>V9Bf`urTvn3P)Q)CV5+XHKdJ#OH*F81a@7 zA!HCo?$eJ~l{)4~XgWrlhNj8tw+|SYGC7whrzh=|?d5UzU||f$y?~bhhQUZ|e3xIs z86Q++l~W@exmEl`Lu^j$Kz9qdMRU~ZOa3h1sHs?A`jqaKVwbg_>_B({mj_6Lf!%mQ z1U(v+zTMt#rgNSt+P>^hT(v3hOq_*tkLb}kW2nBfMbmD3iL@i6*XP|8WKsEnKr(dk z#~_To`soR6T0a5Tif4nQDek+gF27FQ9XaJC<)lRdH@g|1`K&ReHnsYDC)^&6lZX#z zt>GBaaQ88>RDIhGBPntof2IUWY<^MmVfnewsyks#O!8^EwL^o6rduyZgjd9fTc=jD zlr3LuF9oUEaR|fJq=6uA_@-@b3W!bPOy810Kv(zYf|Z@``6=FR>}goRe?+6lNycsq z3$`+y#OxFwxzCf(!h$$B0=+OywX{ucMP`vIu9&J(-JfzgH@2zL$H1z|G$(u@Z)Xm-kc{-TEcd*Lhpe(d9v$X-@StR#NmH zxkRy-VB?DT!#Scp(Pz02(2Gee(OQC<3uyOpW*&{#{bO|7DV#E)KeM~Vt6*s=b&s;H z|Cx?d|IW~$;+hi8@>C4>p%{5tF3aFMa5vb{aCjmQS^qdJWTz-%%;LVjpchn>bd+Bz z+&G__sDRNFHkHZTsb@E^VW*q;@w`zggjT)%t5(edu&04>96;9Yf&3zKO@T|_!V1kR z`>ScR;=00Hjd6AhPx)TO|d2!cu;-dX1R)L6Gx7*HTrhhZgoC4vNH_2 zfl!cZ2pkS2@!iLke=IYb(2HUf_0h)``|Z)-zK1NsO&z{z9eiLS;jTKD!< z2+Ko*UG9w66Ny?uBR|I>VX39)`uQ6h>y}-GzaG`*SmEVTtnYFZV!9rl!KAsKr3jjl zN<~HoWqk9Em~2V16@#>rx+c9>CI(*R^v4@G6XfSq1W8!-T&C=u|Dxqw9!Ot zQ1ROwYo52PdDu!wTK;c7rK3`X62#~_$)-+q*(fB2Hh4V?o)BC=3t&VZmPiz@8oHp<{`*i4un;xHgUH=37H1gdpWEN@( z3}2cmUGm69uiG67=R?Gvt_Gw|`sW%-e^%God+lt0bonkBjaZx2=JsK~=K0oSw^T#E z_!$2e_~e^$lxev<7l+^6Fm_Ufs!dZ-%OrfpXr;HPuH86DrT_R8S9gsz#cj@KK%|` z5HmrKP~ll5x)SD$yyD=@x=y{T-k_47S?1t*;|jYnc`Ki*<4q2}cgF2+=Exl~*t>+a zDqP%RiTgbtgnd}&h7Ybj)d-rE(nrt;r!)ER%iNHctlwr2dH&2B4^Kxhkw{#C^8>z< zp5ZqX3l0y2I0~sr7oRu8PahK3Cnm{Odt}ir_@-Gu&)G1v*~|Pf4eX)PNP{f?c{XyD z{z{my?0Bw;$FcE{5Gj6J2 z`ZJQBeX>|Uxze?OH&*t?4DiA1izwJmX&Pa&1;QD~--OQUM8I89{lmmZYP?zSWEcj50GHsZzsC{fiM$fhM&zLIOqogQlU6eQ9s3WqYe0}wl>Tt z3B$d6j1G@F{wiD^OeuQB^E|793kjrM>@oB@lCO7~$=zPjX9>2gW7-Met9Mel1$^@R z9J|j6+#QDjfYMuBELU6u>y%eO`UJoIdayYSgxeGkf0M=A4NrK?MP%L`QbeAfXrtz! z8uE}dcAf0&U*amt8$3cuM?ws#=Psm09(>`4^ae;daHoPjSk}HB)g7UCtQT$}I{*pU zi3;ZD`?ryq(&|TZnj(2UE)BauV5vi9my3aN91*!kOv zP7}+v)74vmeC?Ceupz0;fIuZKhULv`u8S=?0>qu43i72+oIEZ-ops2i`1)I?hNmFn z4uq*ku|zgheCzRSnokr3+%|+^Lg_5|ci!<1Y=f<4Ds_k@iNk38Qr}$RdiXKUIo97k zV@YJ^FM-S!=q7SrD3&_RPljEe1bUxExgv4xVfO-eo~zZ)ad`X|XOLOXxFu&nL$ka| zVF(!4!M>%QI*^2UI}*(o|C} z@ND7u(NgRyK)7YU&Rx#i4pS8TaRfUILPCMieCm|PiSBfNey+MlAPE(wFyU|C0j*cU zxfO0$Wq`kf<_}8)`Bgv5pL?MqDY-o|Ff9Vk$%4LBqOC}dfPTRbj*vf6j1in;6nvVx zDCg@o+O~SCv6i=`0N^La2CeXA%0Xz{mi>C=!#IZxcp%xRn8N`g-Aj$jcqBB5x2#_p zTn9d5&^Q{R`RPHhn3#@re?A>w7gGEQo(n}Zda|dp9C_SLND9kzjOFRKyZm3}I=qgn zy!GR4X@#4VKxQ$93&cN+=`f|neg9Pl%Fdreds1IR_Cy;*HjTHS`gD=0-Rt<*`0wy? z>q9#fS6nRV{ts};;x4~uW9XoFF0R07BjmQ#&Tl?008zXW0)fUaL0$g9Z`r^uZ8^X=x2R0oq-;H~f(9f2p=OVPC=G^lqF&Z>XkmC%xRe`u({15Je z==>Qs2%n;HXQN?S(Mq^F+?@TlJI}oMT`wdqciu3KB&h#vfxF}%{nfBzAk=NR;H6b| zT$lHIR!?{?Lkh-#at!0YHm|iCH0F^yv_})O(^aGsoRZrXwK11TV$n}&=tG*s1**ZR zy3)Y-bYmT;C3YJNK10xxp7_o$P_hy{8mR#UD*iXL4`Ayhb{R1IYDe>r#(aqU?86F5 z*~~?s0zVkec=y#KE{_xskXV!)fBwjP=01ig+ZmC)9S$NZV)&mE*W`PtwL^$I4?TgU zQ3AaEf6%_ybnT>@yBJ4g)*JuG-5qQHA{b^74s1xlXB?6fYp>j*CUkqj<)AtCA@^M$ z*UFFzS&$p(fR1Cl&?xfkUwxX!f%{T#=1m4U!Ao`*ak9a%l&oE|AqalvF>8C)%789Q zZEf?x=H*b7Re^u-a|Hzg`U2J-!XF85zfc}Vc)NnYgYY8tU$2oE$JSDQow;DeMEpGNLr9kc|(ID z6|?3Udy=&A$IEcb_zT6J@Gm43K}?4~4i1AW48XRu7$-!Gg7Dgt`WPm|7+5O!x0;XO z7Bf3E?DQt8tAl7`UC9hyqbIU_QJDwAxn9>x0H1-1iK`xN!v?)T1)3hg>th6Hys^qK zYsb`YBLV&)Z8{BRsi7LBMmR5F_YS2+ZZfdFL@SO$Bt8h^)7k)CL+?(qA@CHF&)_2O zSmegH7&=1NjX~G%q1_b0Cme-q#n}g1L(KC>PQx!&`~A#*nJ(<5OrjFrUkGnc{}u!LkG~)R`1BV`z&iiCZ~$TWzlSL7 z>5laWGbyKEcz20;Wv^IHvhi9=Z(#3ZgZBv{DwI9989UyFX6pW>k$-6>BW?g4ky6+?3LDmf^IQ>|j^xB!`%!Y!gIHE%}TEH(Bf~uY)N8v0^2fXEJAJ7kP zc{6C-5 zyuS)m<-E2VLO$-B-m@CTWv2%CvkxO*F`P($V}gH{r1G&)&5WYMn16;2gGyuC?;d<; zA3TSyA=VMO2PL~nmJ~B5kdOODIK10|)a8{13>)Gj39K`S@dPKn`Tb|=A=!|Fi}px% zJOyfQe09I(C-dMS{Q)r}F(V`eqrZuTt=|?`NKYO5VaRv}hl~Z&gIH?u_b2t)!VuLE zxKAb$fqDwiLuulyVT(Wb7J__3{_j&*jQ5E>>H?V-zWAeCXhQEFWHK>S-=f_^44DiR z1ypt}Wl*F#AMJ!qcOb$iGHjtpnL`feX!wGP4={()@2z|t$jnEahj7o)?xzS)=V?#J zSBK%a6v=LL)K)euIArhc*jB=Q#-Q#>cpLgaDdHRW6!uqcF78@#%X_6m?Fc04*O8He zAcygRr`>m+%eSoCBfgusE`pKiWUPF2TZ5zm3G96aMG&q7#Su}venk~ukitsCaX1aK z$P(~6R$eq6b*CR`T#c~H>NNiBVH!IYd#7u2e6>O>d+|Xr8=GcM?#v+r4`2=h1<4TH zfgt@4xFR(t>psLRkAI3l02r^^eRW(*JJ{ezBmY|KA^cG?5-n_XGOU26?sML^owfcQ;9P?j-OM|HjJ)!%(uzuL71D>kzhA86$= z*}HUXI=~g+EeI{!F^nbG)){ZzcdP4-W|*GTKhKd`T)HS>&#In7HFLMtoYk!hE&!1e zOnDX`N^-_s8AaFh&#%q~6m8WrMTeH3^lbG%90vPL&K>jI0NoFVcK<rB|5b9SB&NoTv*S}kNXs4YEzrjfg+2?E!FXP%e< zkl8D$ka?9I#}zU@TH zxsMSK?0D02TebeVc1%2%DKSO;4uf;S)Q=ER*j^4{D)%QQl6y%byl0hZe6w6@;HrVI zs>`{RfjJ*0i8Y#fp8*8393%*67-HnzlPlwRm3}sCBJ6XyR=@zGwKqFYQ9+JX}_y~6pSeocdh!fkf_f&YmV>b8=s|Q(i2Pkf~+}X0`P@2pUd_H=LE2_Y8lPGobV=} zYEaw$6pa&ia4LR{jy5b^=QWHCX@B+#Yme=%xzy~V>aHN`7^F*ac74UhQ<^^SAj9$1Le%h+L~_X2sJ&Q_CgQT?K65Q}EPpwtM@d5{CYf7@|HVr`6vLF%Acx5bx+N)ZD6ATvdGU&V@u?QoK)_OAhP) z(@?eyVP4r{1>*IJ%a|pNm^ftHRy#WF{?Kmt_+12<{vE){)R~^VZn>C^JB+<$YuLVu zRNYpZbeI?6EBAqPx5FSTe?x+?_raR=XZNfnkO(23Dy&roRe%Vmxi*>QPz&f&=MF^wEI62pa^^k22MI*KwDb!ySR7u8vJ(9*1 z#u&^`0yzMT5xqy-gkXk&astuo+E@4e6x3zmI|v|1l+bI4`wLpfK8b=7IN~#&TVH(c z_z5ilrtTL`%gz6nCULXnk#B%g$^3g5i!g#HAHmi7uuGAo zMK2>bFpFL*i?P2y3O59n+&;=9Zv@YE(9DRA)M3JDl?JMU3$;C-!24g4(uCCfiJmLkqvxom&L_{G|87!6fX5i^`yn+}~( zT+eUP@2}DwKfi02D#oqvs;thwdajkq>zGo+g78mF9idvsu&P`* zvfy8c?I!QYgAiG|_SWJL_g;nf_!zOU{-`eBQ5AGELg~i7u!-ABri}D)Q|Rc+H+6Ti zht4 za3?g6Upf9~BJ0tN{m;p^>?rr$!r5Kx=Ha_DB?beJ?l6R`@teau3F=ft;W%%jRoi4% z;#u)9c=L~L%dv(XyIdDrGj4~SpqmI`$7v8ib;#tD1WWNl))sTMuPFcKo+t1nxWfJ8 zCCLB(Rf}|iAlFZ;-uX$v#3w)GFh5j@VDvs^OuO5Yl@+gd@n-ttT*E%!OjgIKB4HL^ zWQ-O<1U$AIifc<6P|oXfdVX@+K?vEE;TQojUaeAK;wHvAZt}X~t?&;iX5U{cpb68tI#=1{ar<+;t8w*a_zMaocRH-aO6KM%# z7_V@C>klH?L;tdYL>pcgayOQwpGwxp^-g7H8ZW0k+b>s7;A=v)S@*G8l`5KpKg}QK zlxoMiUN*56JBduWHWOiZMjGEYY@f_1MURu3Z{)G}-Q_t!JhMMcN5U`@+x+7C?itys zrqGGAZUvY0aAe!KG5iY+ZvyiZ5aIdd-1TfAKdWiMLJXN#RRWtcX=SzMXz4BX;pw@) z-%o`_0t!TZH4Jl=VA?s3_6?)E&rH`9Mc2}ME*yHTW5c+yqm`?tL-E*>8xvkT5P^Lo z6NMSNV|q^l***O~+=5tS5b#>?Cuiz#m%Kn;mPgS26Q=h2j~|Rfhm(+bmeL}K5J;Z? zzq+)FGGy}rrF_j4_gU<$4+qun$2 zz!dV*NZ5koFZFLVjd3U+v!`e;LkA)H={-^oFA`N}pj@|CRY)k4Mh;jaoV2{)N;^9m z{yY1LRYR?&6)q>q3vJk}iUM&Gfn02aS5_rtx9hXhS@!EqM2{svF@C=K?PfV`&v}IL zD*K7qD2IhQ$J3>cGvYMs^v%|$o&eu_YY5EG^ccs!}FMZL#IM4WjQ+j zq;n{N7pf~gZxLUBX^``zs6r%qs!{u~jTy+Wf^j5vc(C%s}G? zS5c)5`~tCg9Em}|ZD-T-$~P1S{5=g-1wlCOC&tPvGgE8Z_`PST`>+rv^mMiP z%J^@i>p@8xUzcYDIo%f0i_Os4b0%zh8V3~hdo>5muCZ>9PA%-3E-h4BU+*=>H!!KR zEpfRDCph-_T^SfKhrNKI_1g233wYw2>BCmsznBKhjX-|wzckc{*puMcTKaCoM>1hA{W31!H zN8MHCX)(2_5`Pq4HVc=LS;24%w5E`drzc8)8rFZby+D^y4E;W(YAACVd*C{TH5BaC z5B*edJ~>>n!=o6bMAgGEet>caIS=Z-K< zIBV_qaYqh?R$7;{%p9++?X$VX+&as&6?_z0fypR=diWH9z>ULsbq-@&`;|}MAn?Nv z9rY^%cPDFjMlES11^26-C3KAWcVyxjSNcsWzVsD*7Fz8-K99?!zD1X5XV3ox6aJ5P z27aRa37+g}aMx+rDexzvo>c}cLTywc?c7_)pV@_6aj+)rwM4GNQ;-=`f=-Q7;-xW| z#6?IWTcROkFM#_8acQeWPWR&c_t6uF0p4!lEYl?fcTWC7PU3hW{`fc?lF8yE4baNq zh|qlN*kX1!P(WzYP#soXq_Mk^0C^DebDtA|G+<-+|GF07Qh!}m5g`2aV+UaPA5%;O fKL1n4=J$I^3yoKv=_Fr=^WMIxa3e)p`{jQFOAp-+ literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/VUAV-V7pro-pinout.png new file mode 100644 index 0000000000000000000000000000000000000000..443c8cf57aa59055c548c3bc2995383e07132d22 GIT binary patch literal 114542 zcmeFZcQ}>*|2Tdl5ur_HuM`#1LiP$}R?1$b?3HucKOc|hW6%55ZABR>3VI3v0H|)=ym1!*Xuu!I zt;k8he`56n#lU}vZ0^cP04ep1gwvYwzeiFCa$io+}zwyD0F3IWoc;%i^U?5$by1`j*bo(45p)_6B83tQBl#~-@mc3 zQB_ryl9EzWQ!_q3K0Q5MS67#rnd#={cJk!OSFc{>=H}Md*DowA3=a>-$HyBQ8j6UB zgolTJ`}VD^t!;UEd3ANQySw}Q_wS!ReUg=x)zHxR`t@shd3j%7-}?Ic;^JacQR4YoVc`Ha0fR&CPjvc~74{m6Max)YMc|R166Txqkh6 zTwL7e&z}_(6ncAm+uPgWaJaFtabjX(S65eMWhFa1dr(kNSy>qZftZ<@>FMb~p-@p# zQIV06SFT(+d-klEnc4jOd_X|J^XJcJXJ;cKBJSL|Gcq#b;NbA+(IXidnXs_1ckkXg zIXM*;7T&veuc)X9jYbCt2Vb~wL0elpHa7Ofix-WJjeLB37cXAy?CjLi(h?RHwzs!W zPfvgU{(VwXlA4;Dq@<*upI=~LpufNW&6_tRBqXj~yOxuaLqbBr$jGRws(SnO?c(BM z8t*YyP1bcfoaRU4Q{_LiJJ2!>}07^8l9Qy$G@(<5&Kd-L>K+p5@wbb7&A`KvUg`RJHwI3@znY{c$Q`bG2 z9YVC<>MFAY;2wI3l&BxQK-xJ|Pl@!Hxj~F)-!fTi2LiQ`vtcmL?Lq`S5^%Rk%@A<9?-BOB-l+w-YpTeQ=?dSnK3Q%&3^5D)jbC+G}l1s|eR+V#-AK9eDD6t+(@ zs*)VMW9%W2it^&ihk9P8)}XWILMC5;PaN>w^+a1yXLo_c8zxr3ijw&To&W=qRvg47 z4M;zl?dzNd)(As>ay5)bqFhkR`L=p4sS zd;n5-_ovSWye-~XzPg>^U1~uDXnDmR+_`u|ttC8*D>+$}{-1%j=k^zn0#-~BS9b0q z!d+b0?sKh-(#nLTTrURzQobqg-{J1qqORK68p=!VzTbEKHWszn%$K28SA9C0=3$y9 z0CWtTC)uXeV2gpSyQ$%AX2(N7pT{mllqQSPoYIQwm^XR9T8)VV5Sra+B(Ife=tm^E zJ#OMq+IxqC><(Yn8E%EmD<5zDzz$D@>o`)_QvyfAF#p?RaIa3+YwiXdmWs!dg*1I+=}|K>br^itvb9)fdbg1W1b@L@9GTkL7>=! zOpw6sgP>}appm821YVGEmw1nFmd{jp0BQS`n6^j(A=3HL4-F?H(xZwH_%DwEW&|N= zBzReDD51OrtW*Cx2E`Sd9bxmE5jH<7zH!}E%hV${TO~8-wL@9FSt;HGFImq0P zLxu?o-C$+SZXJMqfF0tU-mg6+58V*G-RJLazVxTb`-7CTQ*0yqRn{gaG1!90ljgCn zg>%Ns0i^aHr^FPsw&x(0{S#5y{S$xvhO`be+=0jJD=jhq_@l4$f68#QC!P~rN z$d$EB)s(!&z26C)E6@qq2lRQdQ|<6&uuGwa>L8%|(hIa|IBUHn#sgG4VvLhN$d3HY zXkgvYlS1Tx_e|$6u@Wk{mG?Aq*s`b|6nAppZE;te#-l(76dj_m+);u3?)|0T7zmQJ zA2bF?hnboE1POggs|PGI2^A9IJaU;Kl9Uc`CHud8bXjWizH`53b9OPqTjCOP$U%ZT z#IYaGqY7QKwiD^nPas62nMAp?+nx+GS9qk=JRQ2bU#I3RlBx+x-6Seuf{_1qz=fhl zCrur9(^mS=FZuLm`a+hGPgy}jxKFnI- z4Ir6?z^D>OY?AYe)PiObv3oAY4%iY_Q^+d_5n-CJrJfHrl;3=LvbBuI_n~ zrnh(26El;Ka3R8g0`bgi55aWv3nt~J`(#rK_%mopN`$xh;cI2jDiXRDU!bXDqD|GA zG4tW^+X^D&MIp~U7wharrDiXF8j`bEBTffZk!|LV~AcS}zK5%M-$#2Ng2 zM%D>i<3FODts;CB3=5q|*PKjR?dtI?0D#;hN?Lebvf_cqV%KRC=K2M7e&h&!4<-Vy z^OSI%6t<<-{-yiMPk51CS^+{__uW*%(5z(s1m0$8CHE*F&AG2^%{z$yl;`MKz`bKO zmjI78KvUL|W0RYi<)%fLOVm7-sUimeSXK;eJuGh#56ihl!`CIA?!?=12F^$Kd7veW z2uLaW_isEHXlWw?E|#@`X9OT(Pi>+jbxJ#4ItNbb1wXVB7wUOLRz3mZve2jZ+*3)F z49F!{(gbfg9r5fU)O_UlGHaDo8s+6&MrMl)kB5t9DYu*~FO`+WCX#^ch~)y=;h-qK zYH6N|c$&e66`ny2A6b^7)1m;egiT_$zuqGX`brx7xuMVM`~4%3rh~^vRje_SfoW2S zkxa)D4Q&*fojneZsRJc}kWOO2!Wwbx9v`%q+RXH!2HY3OCU38@UU^I6@*eD7@BTu-k4BG8ivQb6mK7Y@%Qd2vjPhOXLXpVv5i z;l5(Wkcsug#sW=>gs9*-m4?xfuS@$`>tTR9$7~wNkKv&6H~A7aE3$u1c^LB2prVtt zLe-S&3nMp5rG6Uj5be7oNZ7N?*`S#9TqYgo-RQ^4j-}BkAWJvnjksKm_NB10_bFkK z^b4>Z@(l`svT}q#jt|csg(B?bhH#HGZR*~-yU|Im#TEwLTv{TF$dan5}(U-=oi>!@XEu+#yt1;0T3!YG8P~*0Ubra+Fc_}Y#2>x zfqdkemaV`r=SoS*p9l7@5p%jVcp{X4uZ!4_Vpk!Ym$qA4L}Pe%e;4&pmw_8{KyAFo5L2GhJPTbcMrw zVM!!R^?Op5AVVp=b$e_*^r8Thbr4h!x#wO%O5*wA&f+fa)J(6`O%c+Wud;@dl)_j3 ziU?=qGh2@i3!ap^Zp%*c(JJ*wf%$*KV0?dSuZdP@R)5;zAAT?qyHT5_@prIc5)vi3 z#Q4)di78%^GoTdBRPD*DZlx>YB9Nmb?TQSgvi~!-rTJ}!Sg!;K5!Q(C#pVYcb6L|7 zom@bP<_u0eAFUkw%8;bFF}YcKN5=5xK{d@ykwOzKvHI24j}20>-|E{P1kSNHsK7p6 zAO;Fw;5DE&_EfK4@5B&yNi_D-nf*!0ZZvjk|HTs~>Z@+Lc0p7%4@TMi(16_9kWB~_V99i|D;OoTsqUc ziEl6I(z3C_tq+L!Cs7}l+?-i%Hd?3fnO&7X2Ew|_N*07T*a4a;YP`teSPK#>18PS0 zb@kHeojW->k0Nq@;EE~QvtX*_fW)iK9H`Q2IT}H}DEE6T(%;>)7SW%nDXY{i8=z~& zcJ^bGRz6Ids-4{;0Fr7q>;Ak9;;QcIpb&+h6yDoHxN!r_sy#zQ<8N!9<`BgM3 ze?90Y4B_O*5CN7Y-*Co#MERXXnne~T3xX(K*}e|xn>W5B2yZA|c#e6#q|D=Z!`3uk+Q1RmWU)3CEFbm!o6T^`IgyG8n9Ts6xvb-l*Lv_v!9NCq%h zsK&7+cOy5v=P5jHog#wn^I2unit^#497B;xSvitP6aydr(TbFpvxI6|iRe@AYoJZX zNi-4@YHv;Uu<1vG9@j^Ws~6d}C}l3reFOx}sCL@tn-^I6+)UT#h-NI2 zYX`R=;{-xk@V4vfer6#*-e-YZa1*(HNVtlaDtRc8QPqvq*fWA9s_h_!G#Toc)RRK)pW=HK(8Ox#aBO>-*5wtHfrIF;eV( zXddXZK=ai_qisH6Z9>M}Tbp?}>5L(~uznwNOVZ4Y0VR{NbJA4{`%hdXT?e8~jVL)i zk56=AT3m(Jv}ll#<-uSAgk$$cb6d>CSbJm>Tpn*xT0U}zOL8`Uoj7*uhmF_Q3Zbsi z!4gRe){ohGT5oIHIyB*mh||}lfpykpYcN;^?NWwres}9gEA>sk!nz-`fr`l|X&5AN#E#VWLS+LuPrPmb{VHxc)DO@|mP8wp7(hDD0%W*TmSr1VABZZnZU z%2QG{St`+TT079Dpq ztEyq~jd2a*vA;>)pXAaHVZ0YMa?Le}fi2K?lyq5SZjM3Med($(N`GHT@l!M|sUX;L z6Lm$D`?0z?Qiu)bKW;HZl%q7YL@Gx-3I*RZgP2J3HM=b8$E{y3<@ zAYZhrIR@QunHZ^CLc7-zh`k;)NtUH#PhdIf_Ovo`L~#vXrR3)U9%lcS!_K=YO?gLw z1>Q~KqNZ(*A$$?Vpha1cZHmmQNyxPNvU)k2r2^p`m+j-%f4Wjj#Pw(UT;~Tivg3yQ zZzD%u+!~2;Bq~x~<2mm#ApGPFuO&=TwQU9y!l>EEy`0%U?Tw!sp?@%|5nEF%e z`*U608QoTvjnjfED;DT!F4S8GE!fN1jD=>=fZ1^xeS-oRif{S2IoHz)ZVKb;ZD!h# znfExQSd5xjdta;uo`i)AtrA(Uj||0@YA`dj41XHrjGcw`T#AQY1J60(ziBibwd~4O zVRQ7C#g;E@URcSQSB2RPlq%!()i*)(*gEaES+8&AqGv^3>|l0{Kkj<1@j54;`~{Xe zu%>J$ViA;U+&7qa;Fk%F(KcS4LaZdJe~b_n@BN&XHZo1O!s8UQaO2!01bTC~{0!`0 z(=Vw~_5juyU4B5jNhFz}tIL|+cxo;EaI{OrDwi1c)$7)^dy*-s<0M=32PPAH?>hET z?tsj9FTWwBu}`+t=|Q`huUt3o?iahCX!)|;Xk&5YwZb z4NR9jTXN0X;mtZdKh~C7cI=R;vGwgIK`qPb79Z}32(*P!(>aYWEKbgT>WARAJK4+X8!LQhQSM*hPNzpt~nH`uYC<^ zA!1dclHh+5xO5+^ur6s-fK}#YI#-X;HSKO5zY~-w-O^};j@u^yh}(AM4GyP{4R<$P zN^G8r8$LTH_+WFx->vHA7+z|VjQ>G!KOn4+MB}((4^StXe$#!h=ofIZ2*o8VDS)JCR&YDmQA0}4O8`OeKP9T(I z*iri+*w-A*5W)T=m%9Yv-^j<7r~m5iK#BACme#KJ#s3rVpJB`>TDP}+T&jKI#Isx7 z!%Y;)-U#vh?5HaOI_f_O&7GPtUXacw$A7GiT!+*D zjqa2A+)2zymaxiVs`EXLhnBBdTTU+-f`n(|K0%?$S@#&ByGI{l?ZsYOql`Y>H@3g` z%)uWPQD3O*(~|gkm+Ag_&qhFRI9|LsWp7_<=0FYnq~(2GiWMabMM#_9m@bmzLdYm2 zszW1-2>|GK`_qvvmD`6tV<;T%Sj-r!D*1;Btf*WXG&~n~S;E^@4h#c`IaOLi#k#m5VmMLx?vrrL$x7(9rP2Z;xmH3ES{SMDbwr( zL{Msi<#K+|WiWr8j$O*&DQ}m@K~Uuzb1REknpxxOJ_rEGd`jY#y2-|_d-WI@KAbd( zsHxBoVQSpv*fPp|V+o`*e{MJ0yLi#}*^Ufwui zz8`RJ4~_jal-ho+7$3auXz>4}T{unzR!WX&Q!$KtiYcn#iNx+;P^j$kF_OyLQnxp3 z^FV0dH*}8CRRGBB6C!1D%Zgda;@qtbb4k{mPf0mh6)e|*<=6! zMsP=p8c}1Z5Z&56=B~k?WkQg~?7XR%(i+A)fiv4p(a8R`HRv~g_C!)&JDa%Kny?@@ zLlheop?TKb%~Ob^%tp^N#_-!9nWshl=5qz~z>;R>NdVBGRTQ5S=^W^~05Ss%u8OF4 z1h?9Bkf_VY_*>Aqnmi+2_e}v&r?+H0hIwOT0$gBMr-Y&U>M0?zY<6WQUQXBBQ-Zk0 zCbC28I_Y?l>+tq@pHFRD=+s+e!(I;8t0LLhqayq=-nofTKJ){jh{$hwvc8tNa;Nel4sm~Y9_+Pd{w4g`R<8GH*2s;!;F!S z7b1u9<|z;L3fPUAG=(?|nLQp*QQeUV-&UMVtWZCHw&S1JSl%(RhyX_UFJXU-5@GBK-wAXE5Nk0!VZ)O zg2WObi-|a(kvTekI6K2CF_D)95Sy%1Zk$D3s!Kh~p};+Xk120^8ayQUP5x7TZoXw* z+-{%Hoh@N}7a5 zd7M4*@3=;G23?HqYUB&J`o%Ejn#ksq+2#T7B^C#Pxp^h90P2t9mb~!MOryFM*1a^= z1jQ8v*MHVJ{q6Pkal<73+OS^9N3@@Ga%f_mSDNn&F|FbWGtOEOV)9qqbUB*WSI11f zj*%OKCvAmaJdR$EJD{6~R!;ia%pW&%h_n+33)TP8fSr{ac^Kp1rvtYtp|B3E(6lq1 ztaBsjhaO+;Hk-H1*j8Gqm~MK`+Ic2&(meZXKN7A9UT{aF=5^=WSAD^6xS5Nd_QcGp^mdQe`wEFv6@5+0*EauYI?oh}Qo~DWZS1E% zU)o^qS5=O?%sAp#kQ`MzEQ(9wNU2r?Ukb=i;`+d^5sLtJSzp6+nxQbqct@d zP}+t4b47*z=66C18quTukMMSdEAm7f)?ot>ZgO#*(qD`7M8eUN zEsClo;g=gl(MNhO-U8z=aqj(4`aFf9}FiZCsQNUqpQ8^p`3VsL>YU^ zCGh&3S>R~L9?x2BnoUyUWiNDl-KWL0;cZjLW{q0f=%d4kWSxUx41<>ebgAg{@Eq6e zK9`7;&)Nz<9kxZ`V%Rh23k%0=*?CiZ^1c&nYgE02=eHD7xJmF&crGoP|E2vpZZVjrH$f9_Up#YGNW0 zTg_>cUngk)lfjnz{#(ZkY+$)M|4j7)HY=vP+j*v0P(8vUIiwrAZ_lw5HfFK+joswX zb;`fu1t{B!pNeBure934-L;gY;`;IZ!RWf+pE|KtT;}OZ^)*kG*m8^u@8@8c3o(i! zNnDoc3SO>!n{3{AvsHH9Xj2?vdcV8B*?Io`u^r;E#P?iq%4r=*p)zu#Y0Z{#NpBs; z)cfbdifbFn>W8G)G@+(4a5^w})yc-=+%340mR(rR%e05xYt;fKf1Di|*K;00>TQl1 zS-aT`dJf?e0j6OVXwEz*8By7Md4yD}j(J3<3Skno!AZF z6QKO=lV%S9Y)C%)Gr8Ny+BBbONIr2Um&S z;DYlh-TDN<3`D(vhe4HLX>#3Lnau*&2v~TiAq_05%ydRtGUvsb*{a$?`>VQVvbW#p`im&(wYAGb?v1-X3k`-^u#O$*NF!X zaZO?jR2vpp1wwu?cm7;m>fGu>N)*$kNj9g5$F%ZcM4ksb4|`L=c#lQ+q4%ThfzRO3 z=$7P&v*<2ufP=uS95Oi$)v0TJ&Y8mVxv)TE8`|A=>6FVR!O!^z#?adBMSG-DUx+Q_ zVnkDzB$`>#R^xRu^?(|@dECCi-vI>{1Baa>iYGzBMh9}()1!rZA{>!jHJN#ozi{?c zepmFG5%2P+`G|Ua17t-@NEOasQdv~>AHZ7Mqx_yL6kq;VF zXzokI$-0Xq0l8lh>(%crGc~Czx9xIZ&8mK^4JyX2i~hy8P$Eg>b>H#vm5T5&M7XRI z|1-no`zl$z5gj^eCI#gj;T9{Lj{O%&)TD~WRtl!!!fG0M580p8jSy4$RvffbdB2-7 zpYr(L;UlaMx8H5$y#9vfUcuD&1V(HYD_niUZWLH#`6=0^(;9WOny61-%lbhu-$x*Ct%Q43Qd1_OOs^rLwwdlog|Moz=WtaWKgHcxBZwrbZu%-Lz^Pa8ObO^R79l z{JE;_ni&l9O-^+9t2R~#p4HFFo}NIYJRWJM<=|VH?%6G!D zc2`J|OuMXHp+tRRXF*>AXY=yyl~dz0(( z{X{+KrVxKO^!t`n96`5vNi`rDuV(j1YvZ zhbpFSsLxee(mS3_$bQK~VXDz?M90_J0M~s1;Yo6Nb8qb(SJ>R9$nUUxH@M}Q1C2t- zUCc3LIu`iA6TIgLi!ke7p!Hz`6briZot&5HV}r4rD~Kie<>pqEb!K%AOb*)#L9KWQ z7pE;ASi}~vMWN0w=Rh3|fTW6WI!SYvgx>(e=SRt^JGtYEOvBATl4n`3*l@^q8yR1> z=J9AzIV?u_Xz`W4i@H%P%+ftpd;t}G-4Sc9k4bnkD|*X^mw6V0)>}f_OV7o}2Udc>{Ohg}fvcGh{{iD68CoD|~x9Z7}p9#oBnA7Sq>U}(v7 z^J329Y0Ib8GsT{LZ){`TnMg2cp305Y+@JoaEFmAp=5(vi#iE<~<|Q63ia+#L<5_xH zD)`mAIS)LsLV1OIbopwTQVRELNu=0a_VIIj4}B-!?k4xQAlp7@eZ)C)t+4Tf;h^qS z+>xz`4^)wmvx+GSHo}iDU&OMH|D&lqYw6y$9U%*>kRJP&OGk`iU0lCDE%$NLwj>XV zQ~j1wGCOF;9XorEQ2;!tx~YP7lvIsS;G&HE6rd|6{<~b1lq*_h!G>XZZl##Qb5xJb zeV=Eq^XNPmtjg=>E}4~mld6!P-Ofb288B>A`#{FI459|P;TWeJc|zD<;Fip1`OtuG zI$8Kc6ITcSt$qg33c}m!{ToKHq-(xThA8?3l*ZXYa)&gzyWC>=N4oi?6QJfbs~2fEg5 zt_>T_A9l8+2~tVvyj7^mazgk)r>?|DUUo0I$-gCtL>KLy62s4e6Q)PIbG~k*j#%IL z&Z~mB_^LZ}QGl7XzTkW$1=i6zbLAzR;O5TsCDM2^GhxUQ-|S2e;_~A<3yyvdI&(pu5~h)0Dl}SmQ1bv03kLQfyts znfZ}y;y7ylH9Pz|Bj9d`v)J!D=gguvz=Fb_jz`Jw_su?jRbEez1>3m7>y!T2MRJYiVPkIzjkBNhg&03ZSvoGW>41^;W0e2)K$L|e>6trI&D=_L%y z2C(4S%qh+lvx_0gYw~lb6Pg_io>{`WMu(O~tkI)uIhbrCn~bxH=J{VIKtLrLAix%JqWE%rDta21%nqNXk{793y4xm60KI0M2#DfDU@4Oq9*6IIiyz+# z_rDG-^jF9Yq@7@Cm<|_BiPRp-g0@KZSmQ`)um9J_?-SqI~i^f&WhLo z%B8V#Qwqh&27j7i#hlOB6u^pP#iSyYox6l!<3J5Yal34b{H`2{$0-(7Ayd9=J5sjc zf(m)vLIloWS;rzSfpfw^0hR`<_Ax8sf+GPJhfti#(?fW7>bxBE72~x5)A3x}LD` z_t3Bjf}R@dEhVRlOr|Q)9uECj9G)I)BeepmW2|Y*jyBe(*kxNF%Lf2JXtL~l+)};6 z8{^{rwR6|mE(`@;Q{L+9&1G(=nfYoRbY|t5RT$16&tlLLqvWd=Pv(~sc{e`|PANC2 zkRjRT%75tAceYf2fm)Z>w`3VpKfPrvhI;;qcdR`mrqr+yZz=y)Y}5&#*$4zzqJ<+U zW~6HDVBjs>dxt-@gQH?qjt<~xvtc5M)zOuQquhp56UKup%w^>kSkm*~0c! z==NW7+HG0dmaew*Z2Y>zpAb|#lOj99@^xl>%!fA0${DoEEaq?qf9nc84iK+(F+|Zn zfw;+lAekLp#p32yMc9~G$>zIW{@0C(I9e3MR9n*Y^=(8Jg7m>#&0RVXb zG=jWb%#c6*<-bxfWJ7#9d08)~@$y}iWHw|gO8OhGewb3J!mfpr=~!3Gf<)|Li2a1U z5&wH20I*s&EW2FIb>ZweLzXqlxgu6yfSavH@~nCEXjbxlniXu?onmA>Z}#!>luA6- zW3waZj>(92O2o%7w{EFKA^>^EGV~eri;#Taf6uN=_*3<$c|Dfm(>U62QKMBGTM}K@~7Q|V|ViZ@gxBXc1vgfL6|1uL)@76{EKQ62V zg=5nB2~u4XphZkyGBtDP8Kvto(+|O*8(DK=n%!ubZ^n%xl=Zb~rt>8A?$X~D{3oui zPz51Agc*J9%Nar5e@9P;0S^ZJk;%-{qZqax_|)A>Tm1FdzXX36ZB=1qzPd+NE9f1{aj z-VfgbtNWlu9qc|I_rs^mSvw@@_thhbeG{-3_V)sVvN2n_HW{HG#uR)6TUfS(*j6*49 z53yRTH_qS563ZVNbn|CSmZ#)u;5GJEIlo6Ba*}D&H!>(yNr4j9l(4$@4lgo4sRZIi zLU*iE#N$d;JJ!A<{*^gR-bQuG3U&DD`@9zOd&*KJM~6RVi*`02t!Hsq*5;1AQcEnU&d2+u@f0C`xo-ay$VDyTI-Lx|<{yPe@^Rz;%S zc;FWEe$lgGQgV06G`Zg=IWfoQ_;5mNJY;%Tl0`#;@%F)x(K(XO#w%~WV8fHt7$?-4Q?v5zs?Zqf4Zxz zRX+5ZERU~19C|p<pkDX-LU**~qcuKyjvw=eXWTLh!|*h}HBp#2p%UbEW= zgX-Ltzfhx{djSBLpR63a$98i7&RW-M3(kUx?T(Jc7ZHY)Z!J%CSdP;3^2AEw^jR_I zj>2&wrRoMgm-^5L-yxzm5U<_B{~grgYs^ln(szY4T)~Gv`8@Y}=&mlXp(ja(u(dN{ z>6k89!2WU8%tX-(=kLQUqCzeZM>LD{4Lb(wSH7IN`G&;=Yi^wx&Wd>lda&`|g(S z>mx@;YZ$elW`EZwHV6E+iF@?0^T(pl_SxUbzV`x&6NC%wnbi<76@3rAt;zkum&}Lz z6s`Ga84nMB$A&kqIy~9n>ivCs=T~$p&@nlaWi9Ea_h_G2$7&e93xykp1nW_IRRE*f zy{=Q7rT?B5nR@@gru6{oc|M)6~q}Ke!B#9Nn#+-(-W5GosCXPJ` z&adEqXBJ?&0s3p01~!P0E@t|Y4(LjzXgH5_%bnlg9ga+S@Z~y4`L75>;8zq$ZltSY za(tmSZG_Kpzr9wfdmr@LYb9sA#Do2pKL;QiUc+3%R+nOm6Eth-moHeib#oYQN}3Di zWh(5t25&+0bk~D}?lgM3ec^v0Qepe0(CAmF5%p<&egJl4aNA9L2f>6m>M)-JLKu9J ziB*qHxwX;Bu=sH*#KEKGAdlI53ppx7Bw0!}rfLi3?X@8Sd$ZJ!9rQ7AOz4XedL~F28pKfzHo425vdA@hGXI^;$1jZ4pz~a6NV7jG`Z_)KiyQxWt1z74h#ojyD6@}Z~ zabH_3O7z^ik%OXm@5&uX9-V)^k>;)&^*LnCG|m=;|4wD-ZYtYQ%;};&N}J^V3r2Zk zK7L5f6}^<_n7GXDka{}gd!d-N_9f{D<_#QFOA>vTnH!%s#zbF`TPGKWno2Wgz*>@T zZi+B;Ybxi5}Ws04S>u%S?YHT|Ps^9K6$^5TDz7dU;qUyY>hG?lj+VsyLk@`7v zjf9NvzK!2<42J&^6zruKA(-wfdZH^?hugo@HFB4=$0{wz2W@{CE$S~Ua$^Yn=q zZa>K<*ckM5>UlFyCTS4y=y%Nu#4H=V6!zTRS=WQrlD*vT^rsnfycXWSSBjM&a5Ubh zxSeD;- zSnwwPKZ9LxD2T_w%^<>z-M)|Ci&9%ZnIE67W5IfoYbG3(a^QN4qvxxCOj%gnj>R8o zbZ$npeV(SRx{PqRHg6V?Z4~&-dHT?YWBbia6-rSJ2C3e4G4pR|y-0wWr0seCJrkWF zSH?r(Xf9(!|6A!<;o;YT{it@o5ln;oqlqk$dwVy$PIASajcqIO>wEZ?F2nw1D^ca` zmvjegYvHqU!yks8tOd7AI>~0wH%FYBY`?2{3{3K@Z#|=5c>KApupNGpcgHSluT$=x zBd+Ec=9A2lO1h)gk|F(VncljT*_kLsHP0bSKSiNkO`DAeT$-}YTvwLMB>6Gft9$vL zr6lSYg39qA>Tv8+{khvqlneLNl*fbZ1&_MMB-vaSZ(l@42<~IEBLmAdHhx-zL^~l5 zzPpVZ2NkK4-Ql_pvS6?-zlZlxa%X?YGKDo9gpX0mNvIfB3QfA4C$(p9i~jnA@aKnB z-E(gcMukV`vggFsRNG>L2bJve7c7^bu@DF3lYnKMysD+BN{(L@k3SqU<=}H&w-3)F ziQ37fxHlzAG_3QO-H0&G$lJe3UFN5tFclIRCvP4Qsy#Oa6$P4>nf$P?xqePIMP2{r zv62vz&F0t8*WE`SZ6%=&VqmOC+a-mX+m6e&3RPo*hbX?Dgk(M@!Hoy%^d;HV^m7$T z@ut6RU=N;5r$st(w?95+W1dklaRn!NQBfn28ef?7bkNw>pPd*?*i~30o$DRNI3#dX z$8mn1IEi5K@r|KH^##jcJ1`Sc=t5WN8+qSzmSFa4zesIYEaszL)bRA|dwU^HPL1ea9Q_rm5xA)l90QhA z@k5>w8Tj?5+Z)G^+)Baa2 zF!^;;a8~!C)8!n&Sk9cC$z}Y;4<2MO%0%#avyH-g_blJf!h_lF_ofIo>%RdT^ieki z8;UC{Kb}2rn|j2XX*0j?5R@}dqYxN!n4*b8&DxWfdwt09{Y-bq`IIm}4UUHVEDlrS z=g&uKrOy*mHiB^2u@`X^8fO8(`eWR1O2?IS*_N>mu%M1zA^9f_Peu7^l zh4;+ag$ouAis}}dVU1IthIcK0L8M%6w2^f)A2_dl&X-B@@)rp`P5mcvYot!klExo4 z)az>Q1sqt*Ug+?dFX;&2ei9#0uKrl%ix2NsPi!uGHBs5=swSyk@WP}(hiT|e$5f&-wa`Wt|*v&WfpYX}AT9d+NeTDMM8 z;>5#NOl^HbYcrGxeMWV1mR4^hykcvc(YC;!6I`jBr7vh3Odj$>RhU?>b~wpO3g|`M zseRq3$m-@9L1UWV32SLn*)1bKq+Auk$x^LG^1-rM$=?7At!c)-I1|izI(v3y*jgA1 zu0HS!>{@%98CWl%{~l3)WF&yYo)8&KP?L+BGkY)e=FD~0Uer7c0KVX2@Aiz+x_Tl( z`rgO7PMUp21&g1{pUELsc~=Wk&7EV#f#;=g_}SlNnK9}9*!3a54lURTFn7-0P8r-A zvhOY!CKL4MJ?a&>2R*xS(6945-@D1Pn{55YC0PE?UE>pjL zB7kXl1@m^<+L-E1IaA9HZuo(34%|$!z-)eV`P@H0_bR=LP{ZgY0!xJPS=dGQRRkdb zB8UsFqr0_1Om)V(;pkC^(_JH; zN-d%-Tz_raP7IWM+ch0PAePA~KWDaHKKrZT{jwoU?{}7taf@+4Pg!wdXeyKlquO6a z!d+k{1(q2N@YV>Q%gp6DJWI7TsT2Fe7sB(lSAHzV-+=7w&NeQ%kO=@eGw6xYH63>s z3;6Vis#g9Lu=lvrl$rUd6Y~~;4M*HsQW)4=5SQc-P*>XV4Q3-2%nzrcSOWXeR zC8o{&%L7~+D5^xTEnTq#{308k9+Ia$SI3LaGp&t1|DBx3e|i*DXVE5yoOS1j zwIIj~s^Cjp-EVE>{jJnfQZ}rak3f!`!pX&7mFi~|nnzPf7eX<4tDm7Jpx&b{0rMq> zgL8pn*lPYCu;cLdH*NNna_vfiTLq^a1l%2WAT9T3-mH8msC3fX%*~yQaXJ-u;pYr! zDYI@295L&0%=w{sc$YmxPg1Y3G;-zXw^1(!#2(d)v7lmxaz_!RQ*SAOKpJgtjN4Q zd7A;+!0cgkXhj<)`z~tZH2)lQ0qhdR{36OC6~ts3K7X|O9?Y2d;RX-3$f>!PJ}B5%{8zG z2>00M@VZxaCPytPs|ieErc>w=Q5tZE`$iOU*n?n=;=)SvG<#`-kDWx1+O9h=Cbe-# z%v71Cs8fQkbJrw2`FM_)TzEvU0y^$P&XZ5P`g03mywI$?;Qinyf2RnX%RR z%=peAPQnagt5T!p8ux}f|HJtm)o@sG*RWu<6TE=q`&3<(asOb<(be%_oxY zS~V~c2SDvo_PeMXffaDm-=nl~*aRoT`*Om|dX_cw%*#^i8j4?)QKoS}m8s^k^zGj>5Fb;3w^f1_fIC=Pt{xB%cue>N@VVL@c^|hb$xJ#^x$pF8I;TdZ)IRe* zxo*gYuVPTYs~i4u(e)j35f3X(SJ$}8R&%NgC_Z6ltLDusS^P41?yjW<7XY{sBDNn% zN;9RQbZPe8CSOjq(46cIqg6~J_6Z3Z0Z_+b@QL6kgi6_$;w?L68;q?* zDx?%bNY?DzjCG76YX}*;vF~FymN9(q%wSOO&-eR#{QhQM_ug~QJ?GqW&v`!0=2Yn< zhyC;%$4f#%vly(*z^n*xVjtLIjy4|$fFJI9zpCXslIfL8U$4fr zjx2mhY z{+BgQYhDw~1<0q6f(9voh}9sf1G;k~c1hx>`Qg65LAFg48}+xjvJg|-^Nnr7+x@F5 zGI_=Eok3MIx~7kfJPO5~YM49Pg(G76-_GuE7v$0FUz*+HhRxHJ{(5X;<3p>quoE-G z{tWWXWGwipbDp@zGLlgRmZMy%(pM<)q4iM@SG`>DGS`p*L{F*U=K_5a#`Q1nT{g9Y z8p1b!l3ib}1zkKF8bj4MA#y&cTY6SCu~LWa*D{BE`3I_rhTh7yh08E`)JR|b*R_N- zsV*-w# zP~}T3%hdz^R8TY5eI?1lDw^VbD%@HM`rn-j#U?^<4iYTr%*?t$!FSwaN8p|_&nb!G z)hX$Y48BG>pCISqEyJJA(AJ7L`xGj+CY&`+fFAp}v!`59%Yw=506H_V zc7pL8&DfDl&l%^xe6RC0(v^$+y^l}b6Fw~+%e>3~%YLEfT}$d!{%z8&t}LFd4yb1% z0!g9AqCos$HSkd?D)x_O?+`dnuxTW4vSAV!n^&iIW>?JfJg9n3XBL3EXcI>xt(~ti z*Xrn{$$fy()-K@LdhuVzq2@nc>mMd{X^!Q7E6o?@fVlIV+fJo+c;$HFYLnV&YsUHe z*rXA+tO@4kVw~XHBJ7cL&l&SSR+WdgJ{|J*N=v*a`LGuq*rsi`6q5SzGPzN#i})cV z3|@?YH3g&%H(FW|?e5G@1cN_K<)7IsW#U$FEBn_2l7tNxig~k z)J`BUU3k4|v#hKm78mw(w!d7%7bPO-3QeYX@GRdbK!5>AF68d0UfqCht@fH z3~8FyqsKER+26FQ9`&F=daY!46vSUKQ-ca;GGRpU+QgARgt;h@hQ0^zw#1n^$mP|>ayww z!_PUl64Q`;K)TwkNZz@$H7w*ApA#=TY)Na~LnW;a8yRzhcMaW|v4LhCv6Sv@s?YeNI&#xWln8J^oZj++7Mfnc zBC$fM^Zk#!hE`ZqNAuSbHUN_(#%VJ;G<1rR`Xm=;RcrR0xBo7fV@u5E`a1suF@pr zUS!nm{C*GAh3$+v3W0RU#WYJcELKLnFLXG+CvwhjL%~k2SDM``a`Ds0r{L}Xq8$S$ zGstZsZAS;lVqx@=C;tN^3SSCfRWoYJwr_^8j#w=l6y8!6AJN)C* z)L@LwdsNi&8Qz0eg$+Ykgk?1Tx0$8#S+fgHZ$)%^$w?fu4^TA-OTA>{a!{W7A+` z5iIvDj?h6mrLhLDSnk`k2ZQ9pPViUWxz=Y{ZO;S?>%{Lu3N7|1M^7+oa6AfA+A5bR zQsi)U`vb0=_L%@anMnJ6hq?h!iJFA8KaNLrp)~v{vB9tgdtyU%1$)g;#bT=L;pvk&E z<`Y!p8*F5eW@b?1aG#X!WE3f=;s?8U*HSF6r`rYU$|yZa?aWW*o_B=v#xivdt%BK1 z6J4Z=i~7vcf>W-Hrfjt6v^=I^y*LS22=u$WsfSU5# zI-hdf*y7{4GMEZ--jGhUbK4&TO@y58fDX)cVxY#!O<7d;nFuYf)*d?DULAQXZ90zq zR#yRfBIbsRz6{i`+((_Qn*dh;)DB%Thy?h`;hg5B7hZGi3sQrqpn>v3Y;^axuMB?` z(D(Ts93aBF%w=7;@Ofi9P?(>1`D^Uu=i(O2=f-$RR}&z=%Cf3{F(CJ3ByEu#gnw^` zi5Xu(zb0t>>-T-zQ&l>;+8sKn3q&!PDx+?w?Io&=c8Vrd^njyd*!ysr?Mw%>vE$hT zZV2;B!ORY&6t$L}S7F1~%DVbxL9ZtdvDXv1m^!$tXn9{n=EaMn_qGndXYTW|gR46G zC?`Z=R8Kl>75N{lchob4u^9$S&9wf1_(rFYjBnPtbZ31@_ko#$loR%g)Js}=w=cF> z|Evu=%fZa?`1GOS`Y+eE^vZ#~40sn(Wd-(%j>ZH_ZcgPboM`+(>DF~Meg+24x14R(b+&!{A=U?Kj2dJk3`<_3+*YKOlzV|VpD=wb?d8X+y1vx}!rYDSfEWtT!6n;4VP#tARFN@+_koc!nc4(ZA2`x4y(9909%&uC-c2 z_+Jy@b%VDTyy%i>Du9?x#FlXl6s>*4fv}C0)#q>>6*i6nz_Mn9ro+FNT$V^`RUg$p z9d9Sz6bu1XShD5ohjxb4u)b%jAT0V{@QJ{hf3vg7m06qah9o{(H<~8-bK%>hrv>XR z3|rbLSPjZi56|kp7ULMN2Sg6p2rrH?X}Waej+n5uR4rU#Y;qOTn2S4uPaqOyo2+mkvGL z2ueYo2yTKwOyu){hTK?DYRI@Xn7!aO7O6~IAuOV$T|Gw-gchYF`v{wV5yE=wwQ0Kw z82!M0AKr zR>N3Hg$otrz7+6T++rbaC&wgGg5z$Qed3^j@Bx?ALI3S4qd@!3yd--u)iIFx99i8R zp~o1Rt1 zd^trT>H&S)|HJs1jL`t_Wx?$kXeKyMR?wB3ZBSj2+d=3HQad23#+)|*@JX`M!y)?? zpRN1Zzjb62v+-~DYWO#!{rs_R@}I0tfHV|QL=2-)!z$PgT}!t}sr(f*4*W1Y zM$Z`_<*&1B`IcG32X@kVP-WFs3~?CxYy@#TTA>qhC@Y*8RVhn@2>r5#ex6B zz>BG|X3{rGEF6r!0=a3SQAR&OYmB?WjA#QCcgq%w|E7{~i+oF;{)tqzdF9?M zbxgC!^9VyO!NQgdZ3|2xF0!B>1gZZNOi#j4aOCYUI=7%ROJ2!xYKX07sY+)5T&UVY z4Fc61m-{4dp7ACo)FmsP2t2Jw{yDtXQGULTIWS$obOVUU+7#sGLi5X2Vg4(4OxoSN ztntryBq2&_34y%=S*j=RK%Q_e<2FXzofN-&StATC76k@*>>C53@LCs^?ucPdM=EqR zMNyD4r!@l(8R}WL84seYGOm$+F@ifCce6xoQlwj@{NPm0puR`8nxc+&%4|Qn;MwR% z0qSv0k_!NXjvZpb1e=-#@)Qa>d7dZovazW13uuxyB~a@ z?IZMb)`RT*a}SX+fUa=m{6bji_~P$5T`#mG*LPKBOS=XlP9iZU=C;qJea{DxA=b&S zy)E-bwn3NM66E|}H9FZ?{>&>=WVip^;fF^$f_ZoXFc#Ow*n&BL#`>6_vz1cy ztLzT1JxKRBh4tP^-I1ys;F~VvZv{L3V^SM@O{1yedr~q9R}ExyLkx6`I3+V2jRh_G zT8fR{C4gUU|G)oI0{l|nrPAq$f44gs`$6c>*&CR%)?ZmXcBh~WN+1w8`gHxL)?Rd(fYUZ=%((k&eh49oN zsU=skmcKYHFX}i%pSsLa!OJjD8y@}tb-)xr{t}&PzW|fo27PM=WZk!G(=JWlY6%{? z1fTyJy&27v0r1TH`|&Zn(U@8p30XO}Lo6;Z+F4GGrxv@j_c)sFpdk|m!JdAS%$Xr!ySzB} z;`b2g7UxAOV~>XDaYoBt(?_=;m@K+&$_@g>=>~gH)kgK$N4z9h?3F|wc0unNq*Jd! zx+uyd&37;7M-GjrM#t93Cg55=W*Im((Wj^;L7uKBG}q^i?(PTHDrIG#b8>s@oIFpV za%p_{2Z*%t^j*`iy+--NWz&Ka2M;RR7Da zE&oFWxdkKvm|)`bvm~o&tpKZw3AY2vS;yLn=iJIn-LYci4K>jsxn}U4sEfF48;I*| zSNw3fX|_ZDA@x4Ds&ZnS2MkHfE8vMU%+}$@2x|IznM`ORIL^F$ zbpa2ZlfDYjF9ar%e33!x!Fm}Mi0d`*McT`M`yyVIv)%Qp%^6%;>{w(EQo7>H1)8}QEA2~EFoV#&hmEPh$w1RP@nBz zyKE$vad^K>|A+_S_U1Y;8PVguLgpWQ()tyr-c^QSVYHn*L)?YoG?R~yVvoFO78zzP zDo9MFh`ecdW6eiV$V|t0ZW_VnX7FCdd&}c)rFXC$1=r@b&v)ohKN51;)&%CnK$_Dj zbBDf?M$S_Zh$*o(X1CUsId!yxm&=lB8mq#>l=^G#(!1*Rf0yz6aoNyo`K4wqmV(e- zq`K*?z9R~6-MH&Uu?&*w7*M`Bfbz|vr|bSiZ=l9~>Fis3#VD}l90Kh)%8oxs*hHUW zmA>LchZ+^Pa^5#tbIyb)WpR%ma=?;m;W>tmo9E3oazW-xJz~EZO%gPhdVAmPTxAV7 zgjn2I+cR;pl`(E!A%6Nh57Ww#_a`YPCSUQw6oLN(8VTFpX}P?2KJ(g>@rL1R2b8a@ zu_L55l-mCj&&a(>P$bsudci~Q7LrqCZBA?MxOGPP`;=ZFL|Vyl&(eZhZCab+iiC?K z(;8L8R`L9c#~yIKGV7{*y;!C+YJ<_V%3ybtriCtj-!}1BdhGh6`aP5XY+I#e`eS#h z=^xEmC|_P4`uE;TSVP?TNlmM2A1Zf=52Zasp?D9haoOB&8vea!o?mCZxGMF#eaDF4 zSL}`BYdXBT62KEID!I;ZQKTAce_xO{=@paadH6%^h=TDkuMT{QE))4UuiI*fWs%Jq zRmWL#J5$;_gyNU>+zvu6efQw8T`#r~>Z@2Nh8ge)vxU{Kv0yw%P?6Z{wK%S-k;jxD zRDkClH_1G4du4|H&U(1>=d21ll6V=zjK!Wprxk2mA0HnIzpb-D29UNFn-?#c8;F&g zVCsDh;;6@zIO@+21J)aJv8TRA)rw^zy*7GpNLJUyHA0$02ysxf*}HPEbyulRC-Bzvc>=aVEfz4>(GqRb3Bf+*>C;0dh$a_ttK$Pyn{h z8~%z^b!w{peWeOknIZ9N^Spn~E@d}xOsSeU(Lf6KGp(|3kVGF9=X{dPlJa;LtWRQM zRB4Mlvyqaq%<{-&((|C|9GJX9(XPz{U+$O^m&|+rlH@;-rkUv=X3T-J(8F@DkByu5 zK_0b&Eq5pSoUOwqO?+vA8Tr2?*)niPdw^7c!(eF+Wm>JuR|ae$h2z~pc5ipcU`L6F8__^q4>4Y)oJ1lb(Ns_zndwB{H97&AF5I%eW95fh z*rQ*_p1`%?LO`>5*sJh-HpqQ%&o%!_Iso#w7jFJ0QQF9yEco%;UPBeos=Hph(BILe zuzC#Zgf5aCR5J4(M+~P7wG|CyoAQQ9Otb%jdR`88Yv5h0TR&tq9?>E$=PG}px1)CL zGrS|Uz&}M3{S%brp9B$DSraU_jS6x=l9^%@YM`J0HM?XSMy|ZS<@9YAy&=}1H}E<4 z7<+!$Q9Q|9#V20V3ZC=_H^<)X^F@QzK{0^r`YXlSITg^H(4xOQ{hY+z@(ee3$m+)& zD?K|m>iChz1#gTrSi)l%o3A`D-r+>L9T2Z2I19#!<{-(eK64jjuaB?AQ zkpyegWf&RBd$q~qu8Y@XV^EJ)RSIfg)Dt7YL^fcOcbhG&k2Q>8f8<`X%DS=ut5>2b zJ z6ei`@P6lWg72FOW#dmI+$VcqZd~|=Ko=wGM<>85|3ae(=KY1jjei+`-*5dU8IfE-0 za09udrM+P<*UVj4^!+!#m9UAV-6|SAQDSebH}>WoCpSx_!%@GFZgR1wDK1J|kRvnv z3E|4_>Rphf;~c9W8HN87vR`ofoug4XbIY)?5Z1VQ= z)-SQc?Ymzc`g8y?e^qktnhp}_@c@U>IyQjrF~M{Akeg1?wbkdQY~)f4?jTV zPf!rSV@4I6N@q)O2$=V0zv-^<+OPj*FSmB{=EvkWl(4iCkXdrR?>HytYHxVB$^G~* z-?J5Bhox^$)3M5~s7&x>sf48MtHoHow;OJ78-2hUDcL%%sDCwHvkx zl=$J#k2u?>8qLsO#zuBuP;`*_laghC zpBdCa{@IS6-LmY8Hp3q84mYR+id^2RXJtst#F(WZ#*HkBUm_N-)g5X^{gh2ZF%SnwO8->XWR<8u+2?kJz_sA@=<}a9(ngQPoy)zs{kx$5O*f31ghsg?{C> z*X0LW+QhCwiLwtr*=#hJXT>CL(o*Ol9(&wAsvBVBK;Tz=bkC z@rG9LSGJcH8qZgBQ|+w24BT%$IOJqzN+*I*(ywMmVel^raGl^snM1s6AC=9vX&`A#X-T{(N4r$Q#uhPgYUVudiS9^c+7 zmY&z`U^O!yKsZU4rJ|*&LbwMh6zf{oKww;4D-<%8Q)QNkgmDyd4@Z0_AuIR-)1A)n z+ZHc9;{_e5-WU}sT@&XiEqf^8ILVKAreHbn05Y#6`Ga!E`qYpDnb4(#=B3INX(G=@ zckIx@>3oU%YAQ0372x)&H%*;y)kLgfPS<1^VSH9;H1PPpzOex)MR9ugTjk4N8J{J8 z@o21g)5*3aJXAf>7-x`}qur!vHO3_KV)>nU`3I@pqJLRnW6isk%#2llkrWfX+cSDU z9mmxy0?U-I>L4;pq}!dDC|;rCzRZMdWXujDxuVw3@$BY{2@rRy@1#Q~cJtDdS-Zp0 z+WS=>Hao|Yoc>382j$&L?Wr@l24vZ2w>XQR67y+Zmx^02<4c^FMMbntFj0FT&L>E= zP8)C(kIz;_O8ESKv>EopELe?c$j)~%QWM!zD=8t(~T= z>4F?vx)xpc?;*GFccPH2yp^9eFy?id;`+_pYUEppM|wS(J2x7y2<%dBD;R} z-n-cdPTbcaUSH!ICNrs*Z4NO&^j?%60(OQ^B&pX^;LX=|tyq+J1lOnc6OU^3x6c~gL~o+AnqrW= z>(3%*#SqnkM7FqQ;9WS!mX|^=xC#oVdW2Y}Wl5yeKqd?wyn!158haOD0%9hsm`O?- zg{P2gWP52dt$3eN0tR&)pc6dI$7dmg-(ct&iUr>+!^3tG9lTYs0nx#m#eSaR)=|qA z+#}N<5TU4pSU9r*t!Ku#jg&6vF(SB7M}3!x>;}daGfmxQei4@y#V_H1`hGh?e#qF0 z7;l^-#v4CWZY{KrnJO1OIg$CbQudPXy1aTdoYX@Eq8LmxdajiR#TgwH7FrFIqs_t| zM4Eex1k&d{(9h~Of1G&J1q&Csp^pR`yPqsM$?g8(qt!50AAT@N4!&brfypP=IJIi% zXboT=*bqy%o!*TeP|tu#AMX#>)dT^Tzle!~kR4l^fY$_u4l$G&F@5r^a)Yr!J zt&IDqPrXY5-Z-%*2U!v|rW@H_c)4_4E!T*dH^mS&!}$@vOHxp8pNolDy(m*s_IDB2 zI0ziSYLr0Lye4?BouW>Zs%*eXRirf*VQ}#i>I@D0Sn}|LcaQN~d(#v`yGRnBI$h>k zXr|&?wlb-rOZQxO?!gZ-C*f3Lb^=VxzS@2Q>d`aj<*(1S796LSoF+z8({cqelgEW4 zTzu~hT2{qG8KXf!@tUOg;3AEu0s#fr#(+YSFW;_-BPiERhX0d$QnSSAwW~qz3{ExR zIURV5muOxtCLnY^NVTh9#v=DBAH1pv2cB1yB;>UanbFY%9X`96Y0C&}#Xi)2!p>FY z0*zJ%RF!O~9pa`|sAq@~hSv{SL{AM9UQ2dix1F-K3Rh03Csilgh1vrgXG_a!ntk154kF(lTfHINs2SHY zY9gk()adg}s+5k(;q0-(*K+5A^{pUlX9Jkeg?Al28j(oWsi#}GA@-8EA*NusB23Md z@lRVloz<;9En-+72XV>NaV>KgkH-~;4~D$B9T4Z!r1Oz)L`R20w}#KOBt)eDY*yU> zYlomQ>9{(I3L0(?&*XGXfrH!}>9t_(fwAM#*tSNTNGClD3>}ag|AG%2@|((CkZd02 zZeHpda9ZvgV@urn-R^UavcYwh9m=j%_A_0QGu1D{c*&`!wFGaz=O^lSum~%LgW$^* z72P7eQuVe}og)*6h?^#*a%=vZ>pZrAkY-qopyU$5{NI$f!fQGDtS)|f^KI9=w{E0k zu{PaxX9SD+Jh50`u*)QcXy>&IGyNXMv#(-NA7m_UMHuDGdMynSZfHc>NFVPFS5l?C zLa(PU30p=IUZ_?N1)XL5-eXo;fA+ZFq{t5NN&@Ap}SQR1>r z)6mMc6Cxl0@mvo;K4$$=c_6uOc7Ny{K4Fg6l1)`qg<_ox+ksoki#fV7sq66h57hWa zBB(mIut%pSYT`sGAys~n>%Ls0NVhlQ-=u6szl6}ZTNO^z19zFFcxh4Yt^+jk3F~G! zxK1b6w3Q2eez=;r^P9f2BbO)A?WuTe&g_gDEkw_KfCa=AM94D1E3EO8n=>IDm(OHP zSo-!Z3GvcX68+JGRc?O`JGTw&m7&XYhM-$*JY;1aUkgCwA`!G>T#K+t}@<1U? zu)ryK+3%#+ZN__jq19S6U+t{~p%?5&wA7a^eUem}>->Cu;@qyhUc56RhE8#7<$yS! zX83B{L4!7iIw9EWOHTBP-~%vr+L;>kHa_8VUPZvAgYC@X`-T@t$0( z{(zKy|7yew%AQsj^sySr2&*sG!sou_PNvAau-%cB7-|d_a2Y+&65lSh8xrn$?Euh< zMu1n(Xm7?lqSlg>mTq3>LqS80#g^{dQ^yK#;7Bs@D>%Z?(W7^A6ngPR_3gFwksc3* zPrtU%a7NRoHu>t+c+3uC+Bq5~biYI#YwWdEa!jzFI}35>N)PABSD06gA}1GQQ3Nanw7jg zqkk@bvL!j<`)gb9K?BWc6RJh;;yN@gyF`89mv@r__DfIRJVhm9$gh3D z0abyXlp~DXwkrN2U{HCiF-jL}e$ix9N^AWPM63K-4#`_$#<+S8C>p1{xSJXvy{2-fgB7fF25-&24ppx3%a)B50dTyu*e zFz|1h=-^#m!FRFyAks{}r$9pWOz2YtXIFbbt*(6aI|@XrH5DeZ|JQ4SE6=|tH6PXv zjgnSr?)s_|z`EjH0rEa;PxQ2l2zo|HP4{B}Vp9%8k7GTc`?5ui8*5RHY-XWbOQ~CL zmx$}ZSDZTryoMfciwbV?AyhqnNr-hX#obE(%F=OwI57K4tj>xhVvH@kb}XPh#D$Vt zta*J+-_!pM_E58JwSv_|3@Tup$FncImWguF{#Y}eq6>vw=yW7b3a;`N)#>k%q{dps zocK>ju6Z4U&Lv6`RI<{(X#R}dF?6M=PNK}74(hL?ddIeYP+8>+UTsXwy|fHUh@5v7 zD47NTG2m`^G~`Csu6wN59hrL1?rgHSu^tA^dv39Ka1M4oY6!U5Y(EiTIlRp7^Z}fp z2bAQCB#|Eq}aVWc!kGUEcv=u8$?eN`3BKa4gCv*AFBBSaZ3opiHqyQvlJPu3~+B zJwkB|kC$=3ohIq zRQMK_guPt6@68xDQCQ*SVaw^f(pz(kRFq^lbl`Wv^o(k9TJWh#-Kr<+H}h@d)6;^5 zeW^Zk8LlxZAqlqX{&-bLXHhd$WLadoxw`p4 zq`jSQ&y6PuUX=$GVy(cH$}lN9h21N{Gy=Fv#lk8eXibKw+NQN;_v&e1bsUv5RbnAdN2#3@nRyb zMzSXbnOm|B;ra<^V&&E_xHP+Z4}|w(8Evr*TT)x&`}KO>4Cs+Fou2Viu7gQWh>uNt zw4q`aF7%ap7SCN@4s$A^WkT923F5m82kNZgB3|>M3_oXa@72l zLF|EqD-=X7D2!liu(?0 z_deaRR&j{)nT0ncf=Pk~i9`9}n+te>q`OM9m$Jn;;($9cZ0^t47)2U@C^9=qz^CYe z)_wZM46@5ER3NEze3_W)7Hf16}V%RVHcgP zRkvH7AW93UsRM;wO{L|>}pq6 zeg36X&ppJBYF={c1cTo1q@aTQzYWOl+6+Y}N3eoQl9}AiuW|Jilf8B&mQ~H&>OqSw zW@h$9#ewyah?N z$U?vit6}s_OvevB!}d=ryFxnFO3TRrt$It#d?!<_~kk}2$z*G3hzXJrMQmj*6x+LrXWaL`rifJy;dKQPtEJq9#u@MeMLMv1waGjN7<*3e&D@wzUG+IoP_Sz#2vM$&B-cik>a# z1d-pl-U+hKYv7)LV5dn;OYPZ&y3x2^lP*GWaOgkYqu7?~Y2xzpT8@E7C{8<=a$&qs(V@szAxAI7^Cgl+DLtJnC)Sll0$m zy3Rf>Zm^`#KPqAPK!e^_+7HZ0jvqXd_}hl#iM00{a7ouioj-L)4erva?=<8kWu~BW zZ#8)RQBZ_LgW}B1Z;iDIU?0mNMKhnQ6)j#2_*kNi)s+vr`);+irLcU75FxW*d_ zpank)O8@_S^;-jA2XKFfi^zmm8cZ=4Ebz|2oBJ{3{`hr3Ov)_2HQ+e!{?~x$F{zXO zrL@g~AMRx(kUFw5$Q@Y#yo(5d_h<2tH?iqahc%S8k9j0YH#)(xk!`WXxyT+yc3SJG zmXy##+lS>oMRAQyVE5C6-NH#ouaa z={TiaiMq+Md{r%yua(kA`L{`q9s47-df$U6thr9k8h+)K+ai}5ea%b92ju|WSw4VxO98#e!<*-sBTjVBVrk?!XX zapKD|$>t#U!2rnury2A^>Ms6FU-@-5;VV{oFNOO0F9$DWQg1(g{ME!4BSi&1pXC@* z9c`ovXn%PP_Es;!7#@W&lw6Bf9RGGQ-(oe`9{OPOGo7Alq>ZrY_0qt~gHdUO_9tsB_P$#$R)AixvI3A)wd z;GfHW2b&5sPA-eIbFCb4B#e@)-$Mf^eK0%RTj7k+*r7vD17$K12V+FcV%t@>o-`Sn zs3Fu2KqxQa^ey+v*gbuK{M5)cwcm+H0Tk1dK1Xc9)hzY&o4Y)*=&7n>pqXL6v6r2E zlYCeuJ{(r0;U zcHWDoKGe3rP53iH3C0Z=qjWxBa_yz?7K|~}N2>ZGo4{8~5RiRA% zNm7qASN6`DdpU0OvbaCxRcyQ;XlvlvP}K~&4T*b+`+Sqr$myW;%+Clp8VljSnekd} zQX9u?5l)XCpqYCBH1m1d**7{wz4%C}Zdt_-Xnhv#&u7m%UUj18ry%0|f4HTp2J$v4 z>6+>=G^I~`H1sKP`#srt0>s2Y8w;N|Vlqs2{5$n?n*m>a|C#?aPobp-M6%TKjx@vo zJ;QPwsnsFUW@BRu84_U?3&ziKnn$+8_KK0>J+YOOq&CqF-Xl1H)P7NtXNy@OPHs~d z%ZADEJg(}aX7DZ9ZKwKSt6~siF5_f!x5qeF3JM&gl^08f$x;MAdhD+8EIk*-Vh61$ z-}jMK*G7?#_9w)fo$38FoLZ7rqp zaK`5Er&q?wLXlF}1RzW#?4Ttv`2gdPoh}wQT3ySnMCXgsCa;N5>e&H$?$Sta+~Eew zL+v5Rdz=+Kt2?XhGU@Bxt6$fyc_#3B9VN+VhPv(g^8yMq(Rwgd7zqm!eQH<1*!Dgg z;Wt?mcZ%{@s;%s+>j;?_8=cF{dNVgapN#P|PdH5GnNQoqGk-#)jHB9h(9GuSnCWI^ zdva~=yv4Thewo@&v=Ybr!f$VAamxt{hxBoEhNl81&>jcR@V4pJk4RI%Yv~v1b1k1B z(L{s+ayB*XOCzG`+^dEL-ZQ_f7s6wPtlPW;g+>+w-}ZwpRWa0=3RxY$nVPsWU>W*I zEntLk`gq;ywy46nIB2HZL0?SS`|&~17!#0+ur`ag6D&k8DV(bB?@d($Y(Egls)Gmm zs9*b2nMWWo5s$!laTA|g5uErT6G(wCrndD9@|&`yBa!d3 zhfzo-rvMOR(p(RXio6w5RsJAl9XppCK|cQ?gYkGCa5L#}V>-s1#t%GnpDdO=C|FpC zM6jrh!^P&C=L+7mOAy&FInqTMaR0PEYdu^Z`vL?}^D;2#m$9?2j}PN2D*D*q;w#T?i4;+zAxxrL!ncw%+vG%Gxa^#!Z2a9tjY_tcf)sj%Mq;V_hpmN zPshhJatqYPE3d!6rFA#skTZ97H{J0qI^dsl(j@JRVJ8Oyyx;ZBHs|OgPh(q@mTy>R z4lxN)sq$FtfVkHU`FHJ2}udkIux$5;kjC&!`*=>pvE8WHMo zMp%sU8&Mhk6zsQK6+-s=Qu=tjf}>jbt_L&I<`EjM6M++K7r9Tt3SRWVB#t(Fa+nlW zEV`5xImV}CuZ>AJQtOA9zmbv7-`k*VhGwqhsb_%=Q0a_H#9q{;%TM>r{O}M0WlFB> zt-C3x$;ZK+Y#lVPOYe_?S+TgMhTuM}Za2aqmFR{9j~m4fBD@RUW>D8aF*;^{{KQ03Bjxl0L+Ve+OJn}WPrc@S#5mNz*GpGT;{9Zm>2(&n*s}Bz ziJ+A|UDI?uKOmgnRQJu~az^mKrjt$eN{JKhyz%3UDn@|90_bZULrKz>J^az@y}Gd3 z;$0KVNP&#T(x^N6a{VF@MjoiGt6C*UWX4w|;iZQ{fnKm;F1L0_Xm~LLWK@n4gG;K8 zm~e3#$l39kYoJxra*N!~oHSb7qmCTSg=!mQw!d;fLAB|*9r^+aO?+Clbk~{P2kKi} zUY|iDj8F9*mUsng4YS_4yF$G9#=hU(50a*APF&I%OEPi%{{J*if`8DYw&0st4J#O% zx8SShV=#@MyjlV=X4?y)ZzaT02?iEkFD{3rz0c0Vp7t#KoG6=k{E|R`8H3C%Ez>(4 zuGuFEUxgr$X(hL9Lpyp@i|&NS_9UvD*|H~diK-7vY>*ewMp7ubdrYUaT)x(cj-0?i z3Z8fLsM=}?9OzC8HyS-YW&x|cBUVWN`!0QXuCFy}NOO!FP1_oMN85cay zte&a0{m3?gpBD-n`H?0)GL#T8^^Y^W!QEd`w|W0PZR&YCrxmT*<8uy6j;GG=>p0@o zzxU7wyO;jQ<9=8twOYL|bB(X~nYCe%9#tNWaQ|zTL?eYlSvm)->el)?Xd%_NmQNY3 z^fq#sbiIEVm4A`BYQw~*Ja3`rXWyXYa4p5ghkcCZ+uV5m{;TF~O)-I8?@R7%SybN@v1<1qfR7zE1Qbn5 z44!=>SCr4~KKH!DMebGOp7hgu!0B-!Bji&AsPJ9fc45OWEFWQ2>){#;G;H56<%d_z zq^aRU$wn^&7f9#sKHoYTp2DkT$8LfQYz;7W@?xiyYqE?R12P*b5KIEy(yPaWvMrED zFN%Ec;NR3Mm(`oAHfvg|pM$OtQkPBPs1jV?gL0b;2h)NMPgl7X)4mG1M^b;8 zcGpDY2dU7^ebO3o-$M*)k5E5L-;?II4ep?B*7qbn0wra*^7}9#G#QY2`mfib?;9OM z&V0jZeZhKFzDg*H@yuRjh55{CqT^ZBPOz(wmTuoLWBdrg3pMk_>~pFoAEKw%ZZ-XT zKDt3OV&_docf8J{?H74~6vKc6rbw}CJ`$i4pQSI28YAE{Ty)|HHCFMVd_WcO)?0kTz+;#{uaf|d*GoHfJ01jqu-`1ZDs4QJ> zJ2QzqZiw$NJ^=8&@sg-U!ZLKH688~7x_Y3WH&!OJ z(3s@kT(Ab{hD@;{?A{aQLiU@qFRM{}APQt(Z{>C~9dB(zu+e$CoT46AazBAba$LA7 zd9JHoT;_UP#*D{e13n$7AYZs(bA$SgxsDqqE_~Ek{<^V4cGyf^uR|%ZUB`M_%WIhp zx)maxF-bd?RBznp3kB%OpRZ-?0Do%7L0^FSgQGqWKpe|T$z5b2iQ|IjrvodQ)yn&n z({**JG{$tL^%nKV`)n`Y_c(q!^Z-Q6zea~}>`jEaxLjL@0sX3X?aqw(%TT%K?klJf zvJA_)Pq~!5`0;@Abz$+g`J_D;u1gAmHC?(cS?=_6+XXkS%p3C^-?jdIAMhlkMNkD5 zP|w$1Q7WGaZT_x-p97Z$-wR1Y_n#|=rA_y%3$GhhG&(p;8tR=tKpv%vTOJW#Q~x=g zu_N8lOwg`fwHR5fvR^t$sMkmvtHBryfpKv)T6wpguWAW)$Af_c*;BdJ=&9P&ua=#Pw`)jl}%J@D-q$Xn zSCb0*b7uF02eqf@$1K(t#DN}`h?siYxN5$WowhC56S#6;Cw&+gRxEd%B#x2zNEHr{ z!wwi3YLq3w(TM^9H3+?@yIL=qT}LUx=^qJAo^LW*^ z8}UP}FF(i{++*A{B5QT)Nd{xb7S252WJl7k-D;c2Wp6?k8_dS^7S9`X9&uE4D6jLw zy|mIZ(O^DLRY2Pw>;2;mCKGvS3Ief7hHYEuv1#8kzqq`tUgB961QvH4EKV9MuFmUZ0O<1npqYVC zmu|J692$9W-_ZBC;eu$`wzd$x*w!!k<`OK{kGY$~gbV9!TNhyfVDy#sQpFsb zUM|=Hfy8Jp?5r~y%whst2|cm-W}!@n5>grT8XgX zf~n-bu%A+^lSO>-3(s)bImL9^vm~CQt#!|nOB$Z)*Pm+gHwJ%dyJgEU|7?2#1n^Wf z_*0y1IAt)#+A`$|EN=XY6BBdfA zZP6)6GYlZo5-Ot7Exl1fVi;;?f6ASV4@bC&3UpKvLveM7rC-k^3OB1XMSb>GYHKek@tm|l_@X|cZ+j9S5JDgl_xOJu4k+XCjOi>`7?hcp~ zg;jF$5@;opo?Q9O=Pf$13)!c%fGa~H?C|<|tTNUN`|=l3-M+IK=hhic!aXvAiUm7v zn;LUl*!HW{r0H{3C{D^~;+5)aYAv6wI9n7=4HN_EGxmAl?xgAxy%rOm(_PxRDoqo-T7?^mPF@sn#?P1g zCn_71eA>irQ1m~nym!d9TfxTG)a<51U<82c$}GVb<00LJx{_xjs<>gQjTSM!$Dwab zQXDR&XXfBj;?Z0x)|on?RP$!e;Vk>LqNxAladBpSs=g`N$x+jNp)=m}Tj(A#`gfW} z($vjl>$8Hp#f61lSWxD*ZC?1y7&6k`}1eO&|(4rez@F0xP0@8vlnMm(#{y_3knV09|;FU0D#uFVSF$zjboqG$#Z08y>U_ zDRys;gVoWI0peFp6{X9|NBMtTk_zu20Gy=PJ`N4%&i>?~`;DRFf!&mK@8=V10pR=K z|I5$#tUj-$1TW|)2k_(*1J}j>{y`^4*i%e;$ADEOI&uxZu?zXP1LGRJffD8_S_aN? zcmBll%m-z9pwl$!DJIpQ!$<~IUf;G<*6XzT%Pya=QRcjrhTYR}|3i9KglZAMF=f(i#^i{vR(WF_4^2;&hP*odtyNBZ)r#1 z(}?Jwh4V!RMep~+#R@dY4XTR;WXim3el^1&sV<;Pgbqd+#CD?uK11(P?ni07f(YaJ z-rB+cK##@vYf&h+co^9Ush8vrjMKwsQGcrDi3`i0echk1tI3X=h-MjQd@7v5#5d(w z{o~AC%oo&nDb@22{l-=;us)te!)%5~m#vok7kG`QJMA;Y^T|wG2ROn;4W9O-{zrUA zQxvS}tMKex|1>@sF&ug`PuNw3bkTbQIrhXz243)$_x;c*>CE1llmDcMG|Wi_nncnBN1VT7Z z<3pOwQzATv9NJhqjF-?{`>pUbcCx>V2DopXeA$T^)k$?z^4W*M&*`)JYnp!FqVQc_ zQbQcR?Woj%rW+F+HNQ9U>^nm-^mRtJKGcn@8ZjOAZyeZmSPg-Boa>o6{ZG=3hPPZ$ zuing0@rG!e8@Vz*G-~HUPR?Iq-47s|PlGAC{sXJ+ESXpbO)qRLiPifBLJrjQ>DIpQ z>dh_UCrGw%vL7+s;QHyU)vU%YO!%7ZWF}72%uwjm8Hz_!es~BK#!?hPfbRX>%E)2e z8-~q1&&YBCQXhnku0jm6i%Lz$)@~#p@0BSpf5);@mpiIsM)%;fx1w+^_yEew;sI6@xQ#oVmDpHzBkKdySa1EOa1$lIuA&T>QXAYX zx~Eply^PePOl5T9L>Hu*!a?f*R&%iCG}-1Z7@GwSdGQ_eBaHTX((r<9-qrOJHP@CQ zfQo*>Q0ZDr*oS3 zio)7LML~2$Ny=ehLP)P_p8@ot5n5Jb&svL*^+p0RW8j95P=Rfhc*KT+tLP9Wy#&1{ zN#(GO-PdvLmtYw}sAEo<8Mg1eFXwelo?>NiV`MA=Xr@+Ef?D2#OVgYoGpyU?$Y$)qihuACV3raz?Mdqn%}XtK?_F?CcD<5wq9fW) z7_57s<_IQzBqJ7UCvX6Yub>r6F4A5q)n=V^xkjbQ z4n%(3)UVpnV_%5@2-n=Y?IwN6U|{9m7NmFkX83|~lA>9>Mm=CI;T+tkoxmjT8obkX z!gsUu-7^5V>IV8Sa?bo`S|C=DVmPt|Pa z*49HdO^*XAQqG}`y$O;EuI@E1?)bZz8|ax%tdD0;4-ihQ4;D}WPOmq4;zbpFW5AM? z4qRbh2o%X`Rl+upCAj;C1b|fvd+?pTj_l=6$I}&_?+C4tvVym& zOYmrJ0j{l1+d5Ag%Xu*TCS!ap$s=0!efvZ_0u&Af()Rmb zge9CpNHr$EZ5phw94U`(u~s>dH6z5%{?KKYQplcNKZ1FyN6-!r2heIC5gB8F+zGH*kBxMA_F2-2HkjD(oO-ckA+?U0B2lQ%)Zw=i)d5u z8?5yehK;2kCz>+c$8kM)K6z*_!5Wu`iPhkJOFgH&TJH&W{l)|^HC|K&M$mC zNj2579<%P%hp^UOCSVLce~^^x$=7I!%8VQ41eHCv@C3}y$Gzgc0s|ku+D-AWMl3_A zH@F1XCEEym1F_Ik@=UtQ`U@3D%^xa#&E3i5GCGKkrF_lw9*Sc92ALg!8yA%x?F{ik zeEhBaQpZ1|_Iyp7YRaYsGkj-XMbg{0ZH(aWzTmpy2YGZ|0=mSP2E4eSi^(kxW0&b4 zzd04^%v3i47Edr@-~ubscEdN=LWlxDASec&5a{defKkGa!4%)ki!)Dm-5nnIA#=TP zoeUnYtS5R4zxPon{Z|2>z25s z@34LfgJPdjre_n&#!=IFmEew+pidw@Py3JtZ%O{6M^9Do^$;*i9oW1nL*b3#y~s+1 zt%!^f?jdz0Z@4i$sEMynsWGLgT9w}UZ5cuXBr;Vb9h5zsol+k|nW2=YT%*-DJztv2 zwOl<61M1;;rC<NYVV6KOvg_8cq)35dzZk5lueycCV8o$7`@S?BGR^dx)*=e zx7<=tVcX!Y*L?u@TYw5(oq%tFh0AYr1S+ZX2BWbpf_lZIxi2lAOK3Hx`>UO;po&_w zrdcDl%0d6J0N5 zoscQktXGoa-8vAdQQng1*H$1xPW?6e33bOMAD79f)Y1-w%Ivj7p+!kgB`{$xK=b~B z_8Gmno$=hs(z7Mr70)&Ea)je@p8tyR-A`}S$+FRdt+@xv{h`eLpNrLV7{Ld@KvhN<8$tBE#v#uaL7Li0T`$dRJNk+2jdwEK0IM--Y^rkuhfT9dd11E(p zZR!oEUrH}0PM2F(Yp|o^hGM$a9{F~QeAS35&Nh7Ks1W!Wz?Dnrg=^_M<`$dgjPL=+E~kHE?o%!OL2lI3gw%64z#UkOo!o~V+Afd;`3tguoB*(#$Nkb z^2!WlpI)&WJb#o3_RGHmAhAPGlZNo^E#nfX!dX`+!^$&fXm#D~!tQ71e_0c3(f(IH z7b^Nea znqYZt1T3!+n5r#5IrbBx+&|~QcEo}9@-iEnUSC|Rg{9@W#S<@4tm#?^*%SO@3qU9@ol z;30=2Ug@cgEbF7%biRrjtXiIxym^%zKQ70H5cQ1>70J&){*rp@>ci&sp7lX?J*KiS z_$ul8$>%5{F~>YnKaWN?qPOH9H2eim*o<3yJ>N@9^vlDYvW<5d^{F-YSNu`)?6u>|D@<69YhN)z}E|#Bi zmIwe^O@#b~tT&EZIHl8M4;=g}u&GmYPAvrPOb(Q=a7#XL?3Q_eobi@Gzl=8gNjMJo z>>o9~mJT6(7okw>nFzu2S8nB<$Fx?U3a-Niy+wPDB+b75BJ56Ih!7n?7Z3vT@LZZ_}qbsq^m^H8&qx-(moMoerJ%ZdZ45_ACwDH`v z$c=D@F}KkYW=%PyztPX9bT?o*f%cMzI{JxJqXQ)fY@@;x!B^Kxt1yH~3DEuWLUK}t zn%0f_y1VKyjdp_BW5o_MmZvOZ2Oq3KVTxZ?$a*eEWN#7zAfE;b}Ehv~2{=Z?tdpFHJL>dAJe&;1GRV zI?+gG+yd9ku*!CbAuB`}A&r8Lt|0gOGGKBp=x6-O<3K;X)tpx|B3Lw?c=M!VQkHGO zhV~t#hl>-*(F8@faDn3hEZZeQyFlaF)znXuE}9o5oKjN*yaUsd@ehC{GKIyY7e|*B zFM(~c4m8p_T_$#}^0T!OJUYW>bR~k519LJ{+vNA#zUF3?98C_5#x-i4s^R{b4_vtiUNJJ4Z8hHk#l2VQ)pQVJpl6d8LrLLw~0|SP_f?1jTzRW z2EJ1P$NkeYB?B^@sH(r7q2k(-pPt)C-WTk1Jjt5r%oer52XtDn#~lBL_py-yJxb84 z#j6u4S7;p#ie^de03l@IV$|8AN?_~GNA*jf^J{e3V}8cv;n{an!}TiIFl%>;AQ(}$ zWvvE_Lk(l%2u!P*B4>RYk8X%Ie|H$jj$MOqqhJ)5<8phiO5sk=0O4?J6xi)Bkg~tC z`Fwhj%_{qbUYF|2#&;g>;vd;Cm4;mbP)(VUD2qtgvOfwIW(Bs0gM_ueHqyp_+@FCc zk+EtvgWAZtx`l#^B{HQ?N~zNj8?TXr@3DD+{W+cknFdzuO--9epk-7)x1OH@BbHr| z^Qa4clVZL+I{I58LpYq3idm=*FxAzn8o901J`;OgQ93|LHkwBKG{5LjcEZO$TBR!5 zDbZC?k~=z|SpeX@eAPY*`7jIi@_0ZXbCHQBrQVrQH z=z-M*>R;K$E`@6lRh5slb|QF9aezL^-=>fH;w_pd7b>pfESreUc&E4W^>PK^ZDfrr z9jVRMPRR(;DA0eRuzlXDaE%M>DEs_-NBIVpz=x>;uMmGI@2agS-O+LP?F>?}>4IjS zqpYhXaoCT1igf)xE>m909rR0)w-OO{@R7YD%kIR?e$D!C<7uwsn@e3}ZW?#2F4!*_ zSoaQb4uqF0Zl3j0?o%R2ot$zzhJFgxxy@KklKxk+i7oEVO(ALpjKSHMAaFKDzpnN0 zxKatBRn3!Dxlh!(3=lK@MF$02p4jGXo2}D8+Qk)pXXv^pp~YFFUeuvR{(flnS2}Q3 z@D9$z)#`P0{NoMt(wZ6bVa%@5E{g!V%I6H^O^Lz)_>P-u0UrRo{yVNi;gx9-_XNI4 zuj{r|*|qaEHM~;V=v)#6a$j_XuA#zO7Db4DWw+Q4Vrr_Qi*FDGpxpXtRGt)^FJPkE$2+w0v1Q}I2RnR!Gs?lnGDn(j@^xqt#+le{`Bfge!q96 zHa$<+GN0o>uWM+>TD=JlAe!#UreKG9n z!~ig}t4UTy_{(v#vlm8VnZ-;vUa4$edt&1kRrDA-Nq;iGtzvCN2fe_<*wC1~-a729)~`L8wK;Y9&0N#Bpy@ z3OvZrTET*jB$8MsNaI@jGZGfCCrhP%9@W!yLCy$KtXYif%3AR}tS5pf5^$8N)?Y|f zoB&l!4&!GmQyvRs{DWs)&Hkpe>E}; z6v6`_V~gRT3qQ78-mzBx&~3lgeIKl$x{e5L5yw$^sh_Hjz2Fy@ zp;6uV&CTp0U8}53_iE`6RLG(@GI%Z%l5kkNn@kDRN9~gIB_%uGFN1IX( zhz`9mTWcnd<;4y5wWp#jUmA_%?4Gx)AE~7qVH1R+H9k8dxM4!Ld(Rrh3>4dU!h5s= zGM__v)@6p?EPPzYq{lR;=A8M-UI1sAgzl*JF*Pl)8xv8XEBDwg(Ak|9(Ca6W zk9rGAj;zVPRoo^=jRH=uv>esBIC4B2(Bn|s1Oh#q?+?wZW_J>Xgr$jt^O3>@W!HYq zMxuSpvZU;8P2p0tbTL0~Odx6bW$bD9N zDbbbcD;^QFnXLg_%!h}WtIZww_G|KB0Df=T=~VUhY5L=wPlGWCMJ$)2LL1AA-F=9K z-bCM4Ctxfoky#^(Iv9&Dh#jJqR6Z&Id~s`%OkUq}uYIuVjoN$N===9izMZ?$I5)Rr z3boOesMT8i7I^(Sj*=EL$}D2c==Q|&h?_HhABjn;@f%1hoV_VkIdnP4|6?R$ z5utA`+xsCyPfFu)p2Pqi_R}^SDcI@&28kuZ4buR@>@2JZbZCjC_IZBedcowMMJ_T& ze_Gx(2mTK0KFwWdMr{F+*yWE*8LOs7o;(w+&P>BbO>{leKZJ9=?+WlJ3IF`p@0_Z0 zU|y#yo`=CK`#*D_^<~nw)Ru&?L|YnzQ3W1_UHtmT#EdChs~x`LWx=GEkHt&zR1S`D z+qK9v(5?kTA*Vdm-v|b=pUL3bK{NMeCU})M+njD2jD=n9lNONk5>s26OR`I^U0{Tlmrh3Ym+lK z11^@nl9Xw=rLNBGa+#_pCwl6&(ypMtaXX%_>0Ks9MMUK*PQy#nY1d{qc_rJ-g~o^p zHzq(kZf}HX=ZHYprr#m;RTIUxk|?BL_yfP!`Y!kZuY_`%YcjJD!ShVZBIL?ZMQf^S zAdYD5t>+i_<^499D=Q`YVlJ>lw?D4)=R<{|MgSdb`-cJHJ&hc~EJ1OmqWgN9cl z#ggm_Ye|s$(z<88Vt$YjYU@Xo>3)f|q*Glce-_~8J1=up%S|0SHMPlXRk8MX4@tXC zdY&KSO>q~hw4_iS+m{YqXhAzNd-IeCeegN^qelMdD0@@aL|Z1H54z+L7dKV^i3`fs znSa5y<(es!2{-p0I*K3LLkICwK9q0jzKzU(rru3Yjca^MUP1}5FJB8Nl6e>)2AU`Z%-EZPt2TJ&9ac5O_?*9Pj@Uy`3+exwnEU`6a>hWB60(7(< zmU94UjOg^o0js1<*U__DA-_U*dgeOFvn)0UBpzV5stIb9qalpvzVzu8Ult^|?2Ob4 zd$|h*KyLUhqN6*+J_%~CZJ&GEusAX>r*Y05A!Ov;AkjJS8w(# zs+|=Y>uClL!eTr4{W+KtIQ?ggq*#)}+L2X!lblti$*H)x(OCM>+clz6BA9a&r^~`N zjsPWVyNT){?fG9JLqcPnN2gjuM#iS3-iPeT#tr1E$<5az))kc=SPGxA@U4U zcR_xbmHM!GB>GMA$eCA?^~>qX=!;1QDO<%B_0)__hyB6g5gIv#6jJ`!=-1mx45R{K z24eM7k9b}uLmVGI0=R7oLOH%IKooKkx zPaITtIt#q;w`_a!=lk35RCl#|7~1$U<3iI5_BjhHn(C*j(Oq`D3IAKr*>WU`dlB58 z*%*e-zs%@(O!LAcfJ8M~b`Afkz;QM8bIJNSa#@!~ZCEJ9nsZ`ik)QHJfKX=W2&@pl zF8|px!QryQ^jI@>_$%bfdPC%^g|V@0U2Xq!$u;JvrDuYq-l(NJbOJ!FVo$BQJyGu6yLHlrX#5*dzASY&nVf-1dxvexKC zoAg7v4c-9UK8@k2!r+xY)tof*#4eQwaHLBGHp=-zSJCtHBX}oMEpGHU81iWf=e$SE zJkT{QAy1!x+_WcM%``wxML{ssV_4C5fSUj9Xi>8SRfcas(a*liRm<+%+d)ZA^GJ$I zPqm{%dM#p7C$0)_)pHkJc%50NVCNeND~71ytQks*v#o>fZv|M+GZ4fZ}()4 zcpz^`=yX)|<)l`_-w3bIPEAA0b+1f0o!!JT^p{+K#9wd1Ym?%t-t|+Pa#mN7+V;nN z851o>ACXC+M6w_=W^|O5I2IgvoK22TSv_tqwfBEkYoZ+suU=w&#_p_Bz>D?sAZAWB z@4<>PSS$MF`OpyC@m8;?f6W_WI~`T|m(vX|zx+z626G{9(MaP$)|gXPj0{JJJ?OjF$e;uFx@5Uhpt&l-6f{S}ob8aA-!^cx zt?0e%Gjq=FqQF}*rp&wJOJNX4L#l?mr(K^`qAOWqD@lw|PbHbu1uRnx58pyQ9LpGt z<}(L4JU8g z-_i0P@2w@A+*fF_{1w_-r(Gq+Cj14M+~9mt4qrgCnfh}oZyK8EG@=p)jC96sJPNGM z`xpp|%x%s>H?cu$Rl!uq044q1f1x7-FKvGB>cpOoyGmJ*B?ym$U2XwroH3O~kLibU zH%5HqkyZmrb(qV!rM~|>&s1kU&JLAx%#hg+!~YL(E;5$bapxIq<{N8>EVW2vhC@=I z9~-`Y?cSru`RKPR0~@49b8)@?dp6g|C8$OEcC~tw)?`53VbcB!HKygltW0Nssg+d-w92o_o{ih*B}pz#3Bg#~;kkUvoNF)=KZNu1IyR zg2xI)j^L8NU~rwFOAp3XWv>!v%Mqk7#16xZIa?Tx?}ZckN)8mmpY=W7;0KZzCq63j z5z@%sm-uc8KskWwTAl!S(y!4@D}S7H)RwVCE917!D?4uCC^aKLq|F4=Gk!Dg^;3OH zLuIn&wNpMd=52v9JrjA6p-z?f3iE^FS?m^qF?C+waH<+!sT?(k1rcgYOUcgL<;npbF{#>a=uW)Fa^P%(SgB~hd)Z_38_$TeJP#cmRZplBZpXD!k3z`u9z_x zi#~kBlY~M2WN8!9WgEThb+1+`gF3g>T?CesLcjBA)puVLCsjx^TtGeSsE&p>J|*vw z!v`)_pI!3>RH1-0l0z3>!K}!| z7QUOcd$j|*%nSo{%g_Z6Zqo>Zw(aXlt26_qW{Dl4@Wpw9&JZ)|k_#1@`Q1rl>=8Ue zo+J=;S(~4D7%(PaOqcM2w1*{|8uxH4@x6nHPT-rBYjh1u<2d5}T8N56h&R^h7| zE~f{M_F0gx2$>o6;h2PEq!ax5XfQin4#1APwzPC}{C zCI3OkrP?jC&Ur$LlHg6B+8ELYKBwA2uG2*2PhpsjSS4N*Bk7yp*=U#$D{mc-T5m@V zlV5d}DOJBA#5P^JGBMOk?c5IlI%opF912)~l%+I8J0FKmU-jz3oOup% zrn!CRWT^IaphO&`)_Y)(eD4n?MvI}SPT2E?9ZttRn4qcF{!!3k(3$J%2DkpKku~$- z!T>qANFCH#&?`~g+njiv%_vtj;dpWOUX?l@SAsW7iql;vVHQNx4re5hrDe#P1$G=B zW1;ItG+VtQ;#4eOwnYf!R-lO^nS?BlOFxwI=4#AUAzI@uCBI@(4lUYSxIeJ&vnu_epCaX??0G>x*@IvG9^tJAn~^Rb*apLIrVev2Qet12gO z#UJ>26wr7wM>o1e_&1btWgD|dOjUV)2HoNmFMreVW$9$g>EGGh}K>ZeV+F_(t!J`)tO_$RZy%_AEt6l23?l0*2>GJS>@T z0S>T_ThU{J_;e@~dQn|EmgI>r;UWBaet?3D42no=>8vvAgld({y;=*S672_~-38Bs zWCaT&%W5g&ng@$(=QKEEbsMv?noR;D*lc7!J-gpnZ>9mu0jnFmg|36=7ap#Z9mk)& z(p3q#dPZ&&WVWiYj~|l7&0BVBeBz4w#1Kg_uG{J`J}cGHHm$M#C;BjCvqNVXBnx+y z-QkDxY|#~uQ3{;dJA0t8t3VFMnPG`DqY0__!FWGNakE?F9>bI3)cD>?S4i2UKoC7P zAfJPxvh2ov5@!noPxJ-m2I62;BtSsYJ?8{_`Asm%FWHdU4_m_wHvB_hpduOVaCn`i zKgKb#S4~LWv9}nRtN57w$@u|P43y_8c{L&1@~3tKsz+yUVUEV;jOU)yL) zKL?T+gZOg)P?TTr##*>602Duvx^wH15_BsisPztCc!bzZ6^oJnijN;sT^>LMvmnLN z@*U1UO$@sTfoLxb13>MHvZl6Askb`$>QHH#n^o9r@%^$c@0*YF;a4PN!o`)|^5iZU z4c)gSaJmP*h6YyK?mY1BA!YH0)FXYja_zCGOKWTRf-ys!vDeUa_lrHpVS+N9vFyBG zIF!hf>>Uwj#AE99x%<)?DX}a|M2`VTMn&g=#)n43dUz$cmJ3G!j?7i!M~;>?+7A$g z{KgF=EQd1OupdsXJ%g9@=Ol_1E#)40)O_T8F!7w1226)QwE;yn>x+Ple5aNd(*np| zp)M3CDIg7}pmB(R`uUzXafMG#;Pz#^dkniFz=H*S!M7gN{k%NGFNYAiL&*)76VG0~ zq%pR|h4TK6+)A~mYRn>2cq|l;AaE`3pT=sTkqaFx_*KXXBfG=xVRd!=Q#t=^So@U; zX9S-J^}Ux$I%v@BF#hw*RW9m~=H*g{&i9ZF%{76*hoj-dfbZ9-T_xO>Rs&;_89BAz z3k;0By~t|2yJkPX4B?(LElpR2Mdu6P{h)#6z*{=Y%sOXS>Qp}w!ry{4`)Yv;DkDg< z>|#tXF4aU)*LZu&a*TK%Bhc0g=<}Rg z03XCaTT7A7PasmiM_aJBk9d2eUmqtIr;Y`;IWWb3_~7I3#A`qN&_Vq@1lN_btPXrg z{xTTjZan#@bXKh=d|6lXSF&v|?2(}yfV*_tqAYcy^2=)5nbP>iDl$YmsV!xfz4ag$ zBu)wW;0O`cTzzuExyb9cXRtFCE*@6sJ9(wZ@=JAC>9f;E1BS}Yu;2~E>1 z2ryf^x`qpA3>_Rm*z3@okRRH)z4_D0aAc|FYUeRP+bc#C^wWDW=pkd;M}Gt1^hI@b zLu48J+vSKw+PegB+RIBW8vZ;pNp6a`@RV^%AkveH7;DclTbmBK+UxFh0?`&^+eN-8 zUQn0lW76J9(8p9u^qAP+{uta0NdnSJy$LYF=Z7+-vBMan;e%HA^Z9{M(SEkg=d_Nd zpc091K*hP;5x3d&iy0$6G=zH8D!mg2$Ok0wFwXIA4+m?ZqLIL{!x2g!p2({6Hf_nW ztrC30tdp~&?qy8C;&+ui=VaXoezN9^Az!)Q9?3n)e;F&s>kjrq*Z}WP4~EvzuuFb( zOF=9%E6d@zVW;zbtFr^Vaiqho51)Mp0nt1}Ns$>-lqlvBg9dSJmhMU+^aT94D!_m;{)$?|=n|2)Lke!`o9uyqq1Nxz))tbBS?mu4-XHtVTs`7pT zpt;rG-DLMX(Vyb-U~Ya`Hk|rI~t7R zBUfY=rQ@?qUg1Q(!w8Ln(2FmgiSs7%A2XPLtK^HaD0|yU-Q9p@y0ulU(7t75DyfM3 zIKbdd4}y{N8kRO}CcwQ;iecFV?X7;qL%XS)RJ!QedWkaQe&Y;G@nn&b=A1MA*;}m@ zvE_qAo*Ta3+(~q@SLIxU=$4)a(VLeZgaw+h{-}p`Fo{mx+aRoq2d&T7=nqLKNdwoFdOf>-M~A`97}9_F8L)D&HtYaAvf2 zPhsxaZ8>E~Kzsxqw<{=|-P7-?)WwSN;ZXb?!Y2e($J50-vl0G{rcHLH^#$P6S#$CG zQoL2QwMoS)#G7U-F3uXbwbBwVaGiWl^!s_SxW7m|R7TGlhc+2^tt=*1QoOpK?tao^ z3*x5kzZD<~A9tR(UzpNrYVKXkeBPOJnpi+Mzh3RJ>3217P~_Kn*Cp@SHJ{TGtbg4` z*%&w4{#$n0;ma&q6qhO)johLUSTzH%j zF)Gz^;#}~-Z%ESIn$Hg_vP|HijJWM{Zcu%EPF;O)efo}VT^uR2ro+WED&r1zB=gB) z2TzZwDId#B)UdT6&yqt8Y)*1*ijI<)lMqIgqT2S&BJNr6Gdv4o^E;q<6j>&?QD}3+ z`Rj)eLtGF@eVK#=Ty7ABH265*QxsDh-t%LE zH>WISIPubXgis%EKk;K;LMl)4C`Bz?i&NNdtPvy^I<6nn`+iL;@IWnIb?&a2tqo#j zjC;hk!qTvu20ceuX9?2Az*~#MSluOSxzZ~CLbwC!XA1$K?Hwb5KJX?%rqtbhVlWPE zu!%$AGJ^rxZi_w@q6~52YZkM!)aaG*5u}ZlPR))QdZ!h^>yQ@**{bPasvfg38ea-m zrvsdLox$6Q zvUKa-g5EZRRabk42WE)u0Do2GbHpCPTe~Q6`cmea(C+Nu^yB{IfNFar@&-=J`SgW~ zI)B`{(;}FWQa)}62;~fdmnwLr_767x)h&N#VJuOHd9lK`X$0mcN6~azDog!O((qR> zeSuGYWcjZ&H3(Co@=V~~;K-*CiKsU=UJfSl864+5`}MK?_fLNNrQH__0r%@9dK4sA z%#8H@3uiuUhMJeV;3qay5LSQ4li!bNPKZcJ2vgaMUg*w>_4fACiYRl0)JP1YvLekr z613oXyhlou2NTf|1v)_im?qeg-CA_7ur0J4`&Euzr9Z!9Hne4JUH6*rZvd9k>4rRe|2;YP`aOznIljWUPFn}Xhd!sOa<;+AO0z(?}Qu2W$W~>F!BygaZOiS zyGt>X;b^?>JcA|1a|Bxt=R$Ib-pv418^gY+AB~~^80}pc<1^iU$m;A%rAyQH!~SB* zN@)4E;N|!MNk%?s{|Cx%Rw|750rLJ`f>da+FOYx#fPCK04Ke*y%>S<(FJ@j#O4nWQ z%m|LRc>j$|R5-(gw_h&v?pGk~GXxvi)i0BUr}4whw2`u%;fJX*eDZpVU7^%LT2BWE8FT(hs zn1Z|e@)Zph(YBu7z4x6{ZsYj&U_i@<4`~Q)CUj8pW|!3eY+ZQfQvSX7HUbQ~!jQaD z`&s-Nl>j%Q6}yvfF{gsd!%2xW=A9LA*TEuxsX-DaFw>a8gReYE~0<=;WH}^y^ z7zk2yHl?=B3l7^is5-P$c}kyVQ}|P|X0DfVPOp zxGuXyK0ybZ5`B#LfwNqgDRRya54>hRm1BAcHmc|`{bEB$ z_mEKI$Gf}n7R9Wo%`$?8loILA+nWtO9?YotSf)os#7cBQN@f*|eu+f&Kcs@Q5gag8 z)%gz;KG|uR!9Xrv&LuEM+r1*uFaGG=oaWN%fvMLOvzhv35eOo8Ci6SEFVFc6HT-0$ z(!x7@AEboB_iyi=g1xyC=-~c$yqY`s8b2K8ijU~N)=Eg~V0hG?JxTpmJTI$^!IL?P z`S2=JAgu&r!m!>vxj3STF;7g;R5kp%-&R70y0urO{7>S?1=})vv`XXH6ra&MTsC!_PUfZ43oc64gDm*#H>`q3ADSHy@1v~lf6 z8H;*FqPkSvYFP&uCHoJ!>WS67zdFcIEfZ^&y(K48)|dXU-(Kq_i&s3Hw{i;Rdv%03_`)m zHTpv1p{oMdoJ^=%qvfrtkEb7V@uIf2@3UtMs(PhH-(c#LrT1p?7IQFjIS1We_=qle z?B2pCv*I2ft{BO<$3kM_e+NES<8vt!KmJhyb%EFWiKBq1XN=qdQ-Q9v?B0!_s;>ML zN*7apTMBoiliys(k9k7xfB2~zjKhfA@Huav2ZS-gqi(XQwEvm%d?A7NIVDAW-5a@> z;iMpmtb^26CvOowsak)Zr}b&hMKfkIXL6;1eMf!SOK?`Ds|d@%Onwz?t^Ge9xxYdo zxZ|=C!D$kmV>EUw(^^=3+o@8?o}sH3L!5=UPVr)aDL1yS; z1&vSwH5&2$lIdO*uWE=LET|>tva4Y~y7z&WbJS;(`=Mfjv(s7zRG-71{HXSCZA%NW z_M#6zbt~s#&nR&(VgKhx7!u%*y=tkRlU23fQF0^!LG=792%;sPMFoa23Mn4+{9$3k zWn;FWg&@7>-!(Xc=GP|qy1OyUUU7s7RyeS>XY!PiXa3$Tt6KVxT0Tx96DODS9>6*i z+Rs=E4ttYT>JCQ-Yf98C-A>|*I+Zbv_dWxk=B+xq7liJ79K&=zZrWAL*`?EU5@2E2 zS7k?+n{@MG$?@Z^ze{d7hAUT^&CTDI7W9xAx75$zxNh{f97e{Eo(rdl|NN5G&~S{} z5WNv3tp(C#MvxyhFX2tC(wUG~l$NJ;g<3&UN7)k**PGCBv}DV20;>rXJvx{kPFrA^ zgHcs|c*c9L_4^5T+3a<|=_icdq)s0 zuv@LRyh!RfRamL=WaCR^vf(F2g>jn+7#w8lB+TGi(5t#PD>F7S>g{w=szu&RIChlg zng>MV@S_1o&M(FK*9GQxJ4{U2R8cvmw4Y??zlLm2m34Lx#$GI-2Nb@-&{cHMHaorq z>uZPi(_j23!ZUCGAV(egyj$L056T-6OYd}7B%&sFa`EsU{+kldjfNKD%tN&XsV)>G zHQYNZ6334dQg-=)4KPdHRq)?F`K(}(vUjvi&ii%1Ec4i_<*VH=c~=zB_ZZV-0nHzl z;D??aIR4~^hlB`7?=jw@hKvZxQw;rj1N63>`c2(JnM}AKsSj%5-$|{BHUyIi5@J%T z)Cca>;_r4)(7iUa{{NLs2hS`eg77xH95oa|qI2qq-Q{WR|H|ZFUj|%@`^(7=c*sSU z;A>Skh8tajmp1%7NGd)Nc{@e_m})e2`l!dxODTN>*gPeQ{N-S_7nYaBwqs>>-=5eL zqksRx3R4LJvuJ*6IXS}>E%)S@0Y34+g0J0#w^46k?v#JapEE?uh&E;xk<`2UhtZYe zz%2h}+b{PrzEj%6Z$BbOnQnz7j+85Gg=IvDRs-~0JoM&{equslQPzky6NVvm_>okb>L!Ame++(z;_EEB! z6i7e&i!$rQPpK03)*!rjTKQ?Cf?xh73gMq>(D_aR&g-zKjsvjH>0$NhpQ=~OOCpQc zz^w_&d@r6>{HMQ0Z-N*Qtt`e(n|zsLrZuVGVWPh_z4FzE_RNLl@ir5+5kNY zq<-^d2kj@g_52HCATzAxgt(5$k*=8+3jUTW8PLcV4yJUfHAqr#Ez`x(oFjnJ07e+F zt1v`ksP}har1Tz*3GjM8c<%2gYs?Y^$Z_LrD{a%NwSI7>waYb{ih{QzKQx$n(~$LW z$^s=Lvlv{Df~OzqIBp@0yZ!m-@@Ht|5h8M!_Y>YuB_0P@!`Cm}%{TyAe=Axf4=ofi zIidk>0(H=dy}HP^?)|i{|HCg*s^k{j07@=zg6!h3Dg}3Z=WVg}r3+1p5!*dIl3EE} zDv{=1L>>N(Q7(9EyM$%43;i2#`*@V;t6$s4RZOUM%A{s38ZZ-q;vZWng?YL(sQ?{P zXLHa7=lvw6S6|wxHNQf$yLu(9^Ih&2n$PNBI~q#2bCF6oa&c`b~6 zwsv}VdZ+s7Jk&*)rt{pIH*Zk4Z@ELoL*UqfP3$gn(=CYAO0pswDlkW%8a0o@pta zTwz?~DSXD~kdy`4Dmxi^8i;%wgZ@^UGah@S&DEEA#G>SbO;uVwW}TzWHACcpd|4gZ zKZE;)hO|-a1E$|De9P(|`Pt*7jRP?Cdw@opnC8~%$rvRcEge*0JF>yscbX2+A$GO{ z>DW*FN}<6e=Z1sZ5;&J6!7q~U3%H7}_JgN-C3!}~cvV!Zt2zQgh02#)AqLV3L<>P` zf*X=0$6U&nrw@H1*S*L6dS_YlDS*Fp<{Ee+a0?${R$$lk(eL2Dt$h3c>%YOa*O)H6 zQ6ZH1$lJffCOCVOlJg;Woqh8i0C0dyv2yAQ&KP#)=4*=BBCJ#-)ZpS?txXpGIKa$+ zG9HFEdxV>s&r1oxT%siHSJa@|8pYdX4)yD% z_^vB+;8y5d0^f^Ww`XogLI%fu8k15&8qcS?`}iBpWR_;x0Cu#$gE5L}n9gdy?I;gE z$WY?&`$_pXzAF-Lyt;lvf^P%QuG)kNx8#hoI5-If3XA%v=9?^tMt8(@y{$pK>#VpX zLWlnsx2D)XV*PXjo>pBx{@(l-ig9!(4}X4g;9GOq1Sg4(YIY!w4#98#vvF*qsLNa4 z71knu%=OaYqxq%Vn^LC@ok+RyD#R9ptm0|qr7N3|%KnbtZ@I@Qu@UJ> z%{YycuPh|${k)c51io=|VyA&ZkKey@44i)|r@{&eK6qPwR&aIh7)CRv-N3r_=4t0b ztPVTsfXjZ1U(!N%&j}8amdy11AAjodT~yH5%Z~Lt(DRk^Bvz4$qF6I*{jG3{f1+1f z;D9&%oz4_r#R}&h!kZl;!Ou;PodjaO`V#;4vykr&VK}(C_|BeKIdUA;c#HB3B3wmS zH=>1*eO4V0E5>`ofe(}PRlRY4zq#^q#T`E@K^VynE7b#Lk2wqc0pgun6ug5+saPz< zxl~L2%3B7ABMDIWlJ@jrwmGv$#VRGHbS}1Z=++eZa%mfo0(OL=)W4yj#wP}oQx--l z*ytMvzt>7CJpmN@(w_MPR#KUiIb%d?8Fk8#oGN>qJt@#rT8DoS@hY~H@Kv3osti>> z5nSag_77D_DA60{J8|}L9lE>~VI80rmGN^ytu8~lC#dyF61Z}0a1|UqM4RC0*ryCu z{@Zdl#9*~bp7t;~V^{$HFmEYHvy;x(e^Ejs&LvPm85P9x69JWTjSpx6bnuG7tzu|n z4KnBsM`N)R89_qgA0Q<9b92TfeQpm#s)ILSR%QV$ zsXx#E#ypKUU{-(iG5#TeZaXZ{Hv0k{Q@&GBQ2P?FxaR(T=$+ca)%qG-WzH^nw)pyYL81`qNsi+YD|JeKLfGD@E?*~yh zN*zT(`ltwcXrv^KBS?vWgmg$VfJo{2^se8 z4oGZIbON}RqGLtZ2^^6v)Q!XfMjK)vOZ)yLfFclOcf%6=x$w~6{#gai_4Yhr+~`Ew zl8vD`h_$tLVt(v07NN{2;swk)1psSi5nbh7psb40m2x22}ShXex!*{|;g0cA~y?UjAxBU^*{f{1G^! z1zjtO^8=GjiQ?GDtg^#-9|dXuH8pDroy#aw?%8t6lYp{_{f|W}k~YrQrRPiE=iw+R z{$%1=O+j3SeE%ytJ%26Uc-_Ia^BP@)&Uaj~`%`gA{o^Wta15flOKj4a&QXm7E;HKw z#Ty^ytyWnovH{q&ydK?tF-xno=HdYm`EY(C%)svn4?K4%mvmo?4~CDJ0fQ^XBqQ-% zlf(Q!HnG}4wagNmv3=JpuEqix3|g*y*V$=khtg+xUk##%)DFVqD^#TSnM$ko6vAHE zsM}W=Fp;B>51Gv7w^0w2HxF^L?W6QC?=@(HVP_27k^=w)4EqI=c@XcluTLC>$4Q1P zu%R^HW*~>Bop!5j4yjzO^4t#qZVJ(0Q}S}KarR7^2WW< zgW6n|+YUl(6YUg{$g0|*h(*~xa1My69*3|2thvm zC0Bv`Y1_xnoaHgpP<)mBU;VMEM>i^P-?#^RZVsF~_V!NAU*DYX>`kvJJ&PA1Iwm@l zz!#1@yhtxyT`P7sX3P9`J}(5&wg1ZjWWNYWL7jv2^s8%(0&#%wk6#9Y^C23|&6c^+ znXl$B=RV{lDfh=R?UOx(9?$LdD&|rjkUS0KxWVmXx~IYiy-K{qqg7mWL4HN3Tn_tX zmP6<@j`B9`KkBKWY-Sn3J&M4UIq?K3CD*jQrWRPPFFkKp%P$zzCzrV2Q6YoV3~TLk zxSZyhd`19?E*WdC=G(gCTfC_RMoeLyH(X7a&4Lot5i%VzIkhkM9nXIciS*ZMA&*P^r6OHa+y>O5`T zTr6xN;AwXjxoQL?ip99c?>=%{d#1ZtDD{nv%Sp6DVoN<^7oK%_C3W6ZT8bMty!d*6 z&}MqR@1g!t_p5!JdB^D+QMZRs{BYxq13Z#$LrRWLghy9jTn$~^S`12IhgfKIQOE2Xg6PD5!7;HYJxY68W4p=Q;bx`lpcIn$*YQO~#$p@7>JHh3e4FXZP^8llt>fV&S$mZQ^*pWRwWsF-1(h4ed}@;MvGw zAx3JRkPjvYn78suY~QL!kK=KRgl!om9gvQlg`ORMc`L7@R7 z;oP@GS^L~~nEZ!r92|jr-E2cF?;b1^P_}8tuu6GOhg=)|L`^#cvn-|^BBxPT#J?Uv z&9UM`L{`}D`$VP0XY$49J;Y?pS;)^yg#1o(o@UrZOc*Gx*R-xXtW9*;UW%!*;-H&~ zgv*n+E3u)aTSXy+>_qRzG32sguy1~fVZEVP(X(D#4{aS4H?hZSg*z-RRnN(TYOPiI zqOXqqsy%*&>ku@Q&li*PxH6HiV>H3fU1y7cFz>dtRQi*3gr823(MPgzQ`Zu!_N!*L z3MN>8WJ*YD-Lmr@s&S1xB+{2;M+`_EBU>~ z9F1yWku={ugdLT{tL-A|u5GZiHFKn0Z%p%)AIrDrl#5QQ=9y@Pss2Gt5|WCv|s8p?yZ!rMjRWyLlq_g=VFw3Y=oiZwwovj>JSmi-h)O(^|dF_@_0E zQhU8WYOXA$yYnis?TiP>t7c;5DFd)d#E0i^aQH ztTrYNV|!2}gL0!{<7p~z!paHO-Sd@|x0<{KMR}c|;es zk#=Z{sC&}^Dkp>1UuH>@gf&KO(Z!88ED*LuBb!CY9m2;)&&PRp`V5bq-g#k*;ozaj z3LlO?MlCI|H4{+<661`)NHU&yv2djuutCs+xZSAkUnkBkVQl^CY-fL~)YD2XuAP?e z#iD74eoH?+!BWz}S-ymUWbnSb(+&%{1Zn$wkn0Z4mulwdX~m&-YX>hTWd^2fe}?VHU=Ym~j?QQztphPliBjk9JODGwj0g!rT( z8DC!A&Z$h(D79bP0(t*eSG!C7Yz>x23@d~Qh8=TMN^np8g4Xxc?XJr3O5x}FO8Ehk zs4uJDhEe*H(*r`lgG2-HMvH}&1}w=q5foO&;sC$AllSBxp`Wl z&nAv%$mDuH?K>zIT#G#@w%S|sX6^;0x>*d7;sOEzpS6<}s1W&O!+!yX&4c$mS>@e=zROI-1J0^m#IXUUEuCeVL8i1Ee*Az71 ztCTs*?A0_XAJDDtUKphjfbZNZRx&Z2wHNZ+#suTR7fdGoxr*NuCa%KxrJ@Fp3#RYFj5v+bL~=mtf+ab{PacaO4{{PM11V zaDxSRT{@x{yK&gz_tw#A+u0%0{V zL|(e&Z#BdE?8OJ`WBl$yX@Ah^nScND|F{S`ZY>IjLD6927w5>OOqk7M`F-@RyMcr_ zwL2@nAak`=%8D*xdPPC}4+1OIEO!FFnF6tn3Tf7h6QItOmLax&au}P^Z*JEsES07^ zn?^o+w3ZCokPUHf4E43Z1(KWh)Y0tDmP`g#rZ)$((I4~UC)quSM?6v~+IF(wTU~pw z_SlpZ@_OrEI)S&?-h3HOvh+N%A+*N0i?cR_;_!nAC~HzZk#oSiTlv1PQ8w#cTL^By z8rWSbcIcUJy_YXC7j2NWl72U0oP6{C(&&|s=Qzq6s`Zx}w!uTbEXGfUC({G`=peXU z=|tVZ-z2%($>(8sQ+sY51F5_2ZDLBf!|kMc(qBGIt7DZ~S}3_=?`x91;A;uN`PSgw zlG`d7GoRl!iTrs`dHt6l$ief?n354vJH(Xh5 zlqo&9V=ClgflSdk5~i#dCqms`K&mG}*ZzcCoLt+Q?~UGxk~%~8(vsH~Oc zLzd^fuChBWwz$^Vv{-6e+__ynnf%MNU40uvyM4Ts`nvJ)5#tTzZ%BOl0fSA^NKO6M z`}995Q0zt8<=bm$fmE~ez1@+~ah1fR$U?+#@$I#V-jD3@Sxf`3=2GU~FJ$=eF%J3f zO=e76Yp;)n_F8miOmq*g+4d2PPb?;MZnB_3ewrD*KF8&?Z8xz0f2(qb(-34c0G2u; z_RrPiytunp`z9o0Upzxnellr=_*nhzMs3kvwbzev*9lhQQYl_i9JY7gazho@+{o9j zUq68)U%1~C)MgU{Ltnq*jw_qVZ7VR_evyId^THK+1m(h*6?|oN0)JtgY$*n`O}`|!)8Wxzhr$I+7Y^%wsSUe zxoqM{S@WZg*(qtaQ^v<>hn&~BZlefZIIDi2bHN@glZ#0DSh_w$G6o~5{nj0VxLp>z zO9{IOynps8+K}wya#V7KkW{DR zlGW}up6ytituZb(&1$@Ey3x}RYEf^}32~&A&O%WwslM{b+?s);ep23r`1&H!ffHyp zEM!F9N}_lgn@n(SVN&2 zGqQ<8ImHXSsJ;BpX}j`afFIR+qoT87BwF-y@Hr+MVSheiT$Q#mEB&h#M|E>MRc}}N zNo0~y0-030X3c(r;FzpN&TqDOpfyZCOzLXXXbwv*CfV_;Nac-`;LXVkFT`mW)I1&vNZ2^s|U2EZ>9 zX8yV9%6Y9OmMM@VS$ls>kN7-6gTGq+hzwRuuF?IP3VQ&gH}Emz2lWa&7w}P{qV~PW z-#yAaSv+C9d3#&~$ji>G?0S#s4ytsjHHdy*gU!+61%#%OC~3NPlMo4cL1Z2|rRSEz z_N#m3#asn4KLg>9!uf$?9go5d8I-_MG2at4F<>#+W^?b`{2n^96x_fgrxjJR_SNH4 z4(tm<*fuqbemegjcpiCNMn&|FZtgx}xc3y0SahKi#jgJSolF<9UlRf-t-0EcEB9@ipk2RF6m2eaJo zt%MB{Tx$Ot;qT`n__r#2QT2bT!v8B(z(pcf|IQKEZ>e?6?%QBTTV3FTsf<3<%ON!~ z|8493$Jx67Z2|_KT$NZr!$#Lf>S|u&Ni0byk%U@>2ZDY5*2gHDA_#6i9sP_`JGp;ESG3?Kwt-=v;X;C|EF^J|Jc+4O_;{pyO#bpQicB(_}gBg z!~1tN{cTy3srWl?Vc&xO#h|N^pogfDe6| zQy8WcnBVu~&!3o_DFhVh(#ZI4k9(53U4IdAaFjE@`lD8Fa!!PUW&icCowK)pzSv__ zd1qd&t*6LQqXPpaKE&%@pxC*-H-nvSSA@B0npo1c|5{nOzI6}a3khOsFgf65i#Azy zwhSy)Mf{q3XK%ra6ovbe54N&A{sXJ0|I!92FbyL%BB(IV^=L>Pt8KB!2s0yqvqHQZx@br=Ne@8UPSBrD?=hOb_c* zYDB##&_NXif1s89P{01G0a4V3Nv*J;psN`$n>;h?^!XmK!nUiXzc9eK(N}Fdp)JON z0;$QLeY&@$bA$I?+H~f|BU|o*#W()00=MkZjIc;X8wsKM8z<|2NAq}54?MH)*0#lv z&@7s~8!Qm+6BO=pv3wcJ|3ag{)2r(1=90=Jk7oaMZ}9GX{JhR#m^u3Qpi?gnu0*}q zB5v*+=L(-;J(BcB|JIf0-hx*wSMSg$yjOa@l}eJH;Yoa}{_EZk3Z{?QD@v0Sk^37Q z`UY3%+w{+`%cXjrd->Ew_4{r;7`9Ii+|0@MBERz9lK#7THs>?KEBwB0GqA4Ey`4R$ z$=fM)T;W>DUKJfK3BOOQFV!MXuW68K>*D^dypFv0{-#?==|kSc61BOITezF&PRzeK z*7vzUgYhc+;R)fhYl7(@1w)_fa-x21f>)AQ-|FH2q{@N@?rhs z;2YxJ-xpFC-JW@81(6G?84APmofmU%wv`_$2rBspGZ%8W4;$spI{!XAC#03?gl>cD zZ!f?8?fc0NZj@GAtEx5vItz?_RSneDh^8ReWL$0FYQjtMTf|>7X3phfdmpfVy6)Wx zb#;~1UO7+m?oCuAEX}rZ_su^bU>W{hc^!orvpG|ztJPi0EWad4zJ6*ADhYj{B9^*o z^I)(&`E^4}z+T|LYUrS5UEb{fRGz2P8EXVw>ny0LztZ`Ii(uQLx<0AcpU7Wro{yXQ=IbFNqZ8BXzDlF*Lqg4DgcjcdAaGc~s+BNM?6V?2T zoDVniQRjX{#4`M8=jn9ooOgX)+PB~J8NTd(+0|fF`Bgvdy#`J4&uIo^r&hnQ)-^Rt zu>J``_UBPnfRm^(8vF@R_9ycHl+F9@KtPnEA4P8$auGYT%WLZ{qh7_>STT=x2m~uT{?o-S?%!h?0uVnz_^-%IdCcRYocD?KC3-aZ+C{$MO9_ z!p(0(8lbmXO!@75-A~QyPvFzh&{I3*_cUW%;#URt-_kgSm3ini z(2QIZdxfq3iMIcz!03{u^2cZ$?$iQdO}bQK^{}Kh!5;pv$1pZcx-P6O$;#hJR%7>= z|M840aNt2?-Im`Y@;ocreU17{oL=C88L*o~v%DSlU5h=Pdxfexb#3-<5jGQEf`yB~ z_My5@&T_a|qU9HeMJ<#!k@h9FSsxqh_@cYSeyV58vW>q+b=?t|wP4@5c3`0l1 zVZ825j8Co67;hiuH;8?;^s2gYQ6-1yJJTho@Kui?QB`B?F@1%(`$geX}%U)-yG zPeB24X`W2ai{g;|swDnov%mgjq&p{h-2d1;?-Y4F&CF2siv`Os<~skL$fjE3?N>o; zj>~4>8?USO>S<)y!Uf4?3UJB~PUjjFr>+!pRqsm9FL0T%y=D5nVBI>q%{tENt0|(U z((KLpcG{v9i#UFt3lmd+v)6Ejcnr8?V#>zmKQ+InPxBollIbM{OM;r*>R(A#VcI)o z2@h|19X(pVubH+d%yl*Vm5<0(_v>oY~ZGiyMHi)=V|AMtapF&@!sm>8^?WO zIYGV=)$fqDS5fTxS3l{6ICd;gWLN`_$dz|fCo;J(?v3h4@|YK0~5F!mVI1K)R|GgSu__BB8nG@RrS zw$D$xFIsR^zKIyB1={hq&I+OnQb7iY7l|6AVx<*-s7X03W@MFQtcyhb{cuyxdnJ&b zj|GnLBrq`!a7{{R@8a%>)@CPKJ8hGb-bmd>$!7{7)n>cDoet~r+h24`q_kR0jDA2~5q7Ii zh}xe2`7N3O&)HeKw6Y+My4(8)oUBFZH{O&8dPH)1=oag4A2J2UkqDzfN35nUqnjzy z^D*M_Z0!^oZ5eMaEKS@+{fxYhFuamUiM{hGZg8s@ZEgQn9`JAPm|TuGEp#d~&|qSZ zk)XbneAD&8W5o#xWyNs&VhcCIgKt9rkLSTlsW^xYHJw35mlt`~ zkiTfe^;G|bvPheMRU}`zXw`JxOZ-e$Fq72_Eu)MHwv)>~wxfwp*J=X>N8=6R0kL}5 zh5@tX+i@qYVy3SPgQOKY-Ip^NW#qF!LthsM)$~bn@7;?aY7sFXi>5O%flFKQSE2bV z1!X0-ck~czSA9MDA1HjCNj!pX@8SBIuw<{cm09a2ZQ{ANjct47wY_92oru<{VPkzE zHHB|(;m}Ih14LijC1<9fe0S}=yC_66OH93zF*B7f8N`d33*;Uhh!3I&x93kE)2r66tlJ#V-4w^PyP~aLk<<74Wk@~Le6l>SDGf6^UBcHDj zy@hDijwUi}-~0)IvTW$oV31knx{emr5SENqeyt_sFjfm(U=Zbf$3?tIA+%oq1J`Z~ z33d^$mN24Me;|WC=w;jAs@}~3SyLEm*xpqRq6;C`?@AK~No3Ag>3=m@GN3T{{B-5N zh4&AIM|^@q@U5uHZ3BW>tk?p6;GNyu91)s^!K{(ud;X4FF#yvHRMorX> zSxmjR33!Jy@&|RiiN1-K*J*~H3 zON3EMl9?{(;oGm*_2TB@r8$_I6@Y4fXKmJNu912zeVwG=xJ~Dwtw|EeRf)R?xG`yD z2TbFn2Z8=Eez;J4^+)}i3krG|(o@jg^X@xJOzmyinW;DrK-pbjn(OY05AyPLW!{$< z+fc@Xfky8}bYe_l6!9AL=je|OF0U@FQ*5!`v2gO=NtOOq|84hTLxB|L38|G0!bi=u zvTG{-ROJ(}iR6syF2$otdNmSPJ%|NAsW{IEfQx`Q7XQ!0+-kCFns`w|aBq{2qnx6y ziPB*5i9ralwB<0n*>AAOiun`g%UFrUI4kArFGVrjI0zYKfE%E7)JUHjbPQ$Gdp}*T z`LI+rFLq}TFhvs4wrZL*JcLhJi-NarxU_uhyl?{j?&M4ffj(79eBePKMvkq%oXuh_QmqY=x*rR zNl@o{g-6qcfa}G?p3V=%rVM&pgp6lVb}_vN+**ZqmnJ+>%nX-8uP?Ogw1wZ$jpL_o zX9;2VoX-Q7j7PyO-lXl7!5eEIK$W}xL(0Cn4F`&=aU$sb@^V7>SYG=~RtT;UhmEqJ z4euswxOXeY!aOIf<_XzeOGDB|;I80=^aXHB_hjusH-Ui!&OvYcRc%?sCb;0NDF{Kc zk|V;+1bn!pNqoh+>m~}}*)R6_!>FD#@spZ^Zo-%|s60@G0~hst=SfBJojc$?wL_ zz!n|NgducJO#2vR4=RyEMz3nYwQSrXih$gd%#4P4nvNQ4$%t4L;lR1Dl9$U);WPe+ zhq0VfzS=H3WR`mkinFw~wkkYObbRBuu&|yU~XvVGT0@xY9H$)bvGNirUyZGA%`7i&=Wi< zA>fu@bd*$=J(E9M)xizN+?9fb1mD@j*(VRyGA0i|4xUPIb&QDpMQ<>x!H&5cAGFvG zcuWu;9gA?L!RvDBt1zeAOVLAcwCRDEtpfLkznxA0Txo{q6h?g7W5mdNwg`fV?Fuz{UGz}wV<5; z&B}kX@<$!}H!As{bq&LX%1h9F2p(3C_sUwq0U9$lB<1bx5Y4MDgrpaX2&eS>j9Q&O zapq@aZmzo91=Uyi@~7+X<|ugcKyDt4LkVqLVg6Z_6IGn~Yubvs{-kZtqMZ$j?^1xWAualORWO$=T62kkO#tXHRkaUow6czTSm3KpBxADD^&_0j! zq>M@uE4V8n-(FX8RV_M`nLe$f`vClZ8S_}ONHXvUbvJ{c{cm@O+0NJ#u4~o0S|5H#bexkz8_Ev;KSO`MzcV|ATyKwcvDkdkz1VAt?7p>he&_f-=u zJC@op%nH<>tL98PAD9Z{v`tjm)O%1tpRV7fa_CI)c5~l+))pTtT&`ghv4 zJMQeZjZI)lqwy5?bQkn~p4yWe>!M&-UR}-d$$};LcbpdI;>77pfmbJ|8mV3AI8}~S zI<_+3I74=YlDeuYFuL0*;7!QU@pXnz?R2TEKT|Km+LJpjueL4YT+ndH|sdNdK+cOCBP|RZ2Pf=$M zxGBa{Ml%hOavRlendMWHi{R**(xtZr-j`}{7_##vcFwsDfe z%^NQWlwa4))8f?Vgh~Is4Esjj8wN3-dN$m6xw|$dV^)e>GU(LoT)WB1;SG*_E3zE% zg~~E;bU%dBP*%Jl)zBusDs|g7FuEkEE<1@ty8ZxfW2d98|C#7gr`|e5QG}CzuClh2 zQ;tjt|HTV0QFW&pS&c;toL1Y5{JFaZTp?(M*lRMrW_7o!ch%NjE59*Rc59j^<0@hR zU$Ah_<*s159h@c)u6XZaX617#!(!%fv|bF(BuAiyT3EktbFP1E>c-_4;8JiHoskgk zUA0G*G-M>ZU^e*a9p;_VqDqW%^SVnG+lTEIJ1dsr`2~ctTuwl!vE6ez8C{tcK<{`V zwVa68wBt+rdjj)i6COEsmIdn3(J@rqm)cCKdmJ(iLUJPBDK88*UUfMDO%myq#mky` z_?ign6U?GqZ2F-|#2<>YEie^d5jsw$m4Li{C|>GQd$jcUFn+o(u_eu zok_6lZ?c%=7+v^$b(|;oolJJ_8D{3Sw$_k|s2GL*vgndU2$~=Q<_}aWg5~Y*Xurc& z#%710Pnl~Ux|7XwVs$%BarRgA07{L;cc6XbPA+w4)uU^Sj0@Q=FTt2;;{||sZgshU zcSnP?Fusk#CanpLI7ZL6-`?Ts%+#O=2-TvW9`hOw$$>Y_YBkuf z1kdf{Hz*<-ujT1`AoVLW2jjMmmtj^Q}yIJ0h8a8f79yctedlk2m+71ipV8`|A&cMl~; z2ERs}+5ox3-J5q2xF;L#$=hv%#TTdhN*Q{+JP@VS8l+uoh7X#{E63}qu2}~%)`XIB z4~>ktcu~gO@6QU{6rpc*bPnoHB(>4`pwQ2(Y?3lG`&Xd7J^ zQ#=sMN(W`um3?Nik$6>L?=G>Omd2){8=QHDHUD>d^q3BQTAxg@pp=>-FMQ?ztADUbW(?C%e{O$6FN+C89XdpJ$h#Dk8(ni+Qw8^UAziEy2)hXYP~ACq?Lce zhf-=zjsEd#!2TC4-*@m+qkpDm1;@2JIkmP6lj;?~a^g(%%L<{n#B8#Sr|tH+>xR=# zMjD~G;qf-UkvL`EwfpqGMLQ8Q3!78+nR8a~y8brZ-*hHIr3U#1-$HX^+Q5NC=Xo#o z)}pk0PvvJPCrig{H9WSUv37BMU#Gk|zN|)2kgePAzM2r#0*Yby7PN{*I8n z`b$_;f1UW}Oa+#E-POgj4@k?+fWzQ9oNqlb1%ZnbT%|FTT_=!%SkjXpSP*SN9*J6n$ z=^bZcPkQ*`Jnul-PK9KJ)~YjPclv!-eLv)HN@TXzm=(RRQ)++ExQYlGuS?=^T?%gq z0ApAsiAg?^_1$(|?hZYo>)&Ptk5?BmBNb2$cz!?PUDc(>6(54Aojf{Hw%5AuT#iaG zphT9GNby75T&X0P+lc4A9HVP{^U>eF;>7mR|0IdvbJZt1-7o=)*@kb|X*+R?>O3HgI3A;AhcGhuiZQ`Xj zN(c$nb@gD>HXr20c0yPIJm;vNVi)T9l?D66GrH2WafZMG40s1s|6$q}6trL%C+Yc8 z{!V7p8pD$(zn+<-&G*PVijxR^z5;i3+`}#~+q|B!yK(p4F0`c%BSKK;$gI8Nk1@SP zn&rH&E5E}sXdts&#VL)%UR)fxGp`nkj@TYwRxqY0?15CMGv0}|RgCS<9BckLCNH|JZAyF_R12l`%URqnBpvUYpE9@?i$898QtHt$rs*zM7MmN%Asr4K@2G6H6i*71HDd0#34*{ z7$$Uj6{I9()Fb2FJHGUPB>>whgP5zXMP*cEy>`jCj$_cj=-sd*E;LBj*Z-()lLH}w zYZ%Y}NOzOeixPBsR*3%Ie6Ptp7k5X2j9*sDY{y6bxS$?TQYOdKwP!=lfA}Sy(3891 z>tC5-_yEv5-7H(<-SEhHN@FG5cfj3cSuIpI5nLW&#GQ#Uy(ZRO-?5pU&l+Q%j1)2hW83=)KY zlzO|82tk~4FMU*h@`d17D&L|~&7K2D?~|`!qkNxq#6b!5;b)G%&L8Y~`xfRt?-S4C zOHY>;`_9}v*_1;B9mG#1t>VMB7fvOEbh9H_co+Oaq~*0@-vg4nK7+R4evqN>0+07_ zXYbgRP^Q?sHp}>$B%Yy-GefNeIextPWNU(X33ctu?X*zOdv~pyYd9)LOTsx*Xhh25 z5i^%8LQ+^mo>)~G&Dc6_8MSXOj^Ci6fVz)sJv7|T$6RbhRLPJamnW?Sr*$(kudW0& zTf~p~71cfBa9viN-k=?6qs!i9&F)E8C|t6r8nyR`<5r8Cb+`p2;x0;GxnOIOqg5hy z(Yv&6AYETC-Q!I>138t&?~1sY?VP2ih1G1xLD}k>TYYWZWNNws`gM%dM>X}8ys&QL z2E-*k;UZw`N>%#~AUk~-#R9i6t*2w1TW)7o8iQrkt$3XrcXJ`ppc2W8!7&r#woad~ zhCXQp1uR9hSP`Wb@c2j}sSTh}WrL!1671nM>ol9g=D8+z}OhSOsBwM6ZBC@{kV@^yXe<_FUKSC!uoBqQSeJM^DL;nY^JplTlIb^t-8r|3!z&%hKjKPeJzXPs*xP zSQ~s~e~YIu1BG(q1sxs#?xZfeyUTQkc!rcgV0)$=T1>J-)|i+Kjr=j+HugRxApX!} zQ%#|5s@anjszC!s-#ktdK0DhfH0 z3RDznC)|(tbf2CM9(%kK!VKMnDR*ML3pW~?0z$oR5uyr{&c~CTTxjq-4v)2jGvRTx zo$>g_0#SO-2%rI2niP(f-w02%qo1qZ~5syy^7&M$j!*Ds1l40`4j!PT8xJA|~gmep@klb%hcs zk#zu)I1ikKj1iN(t)M{(s+o~#R63d9Rwx1sj&JL7E(|?JpY7w{A%%4_DI#gIX9-p! zEe)S41`-rzydGaF8JfS9U1KuB@wV1Ir8Y*jJ^;Gp^3)n`I7_gjIm@b#K~&Ye3z?Q- zwHt3KwAJ_DKIce+zCT@C9zf;bH|uamkE3m1|E&v6Ipg;9-tZ@fNAuK4j7NKySq-b-!%)4dLcULSBQ&C z^;<`M?vYAv_I}E?zir_ED9fa{Vetk%0-o>j+TisG)PdMxapv0#SvQc4)sEZwVxGWU z^O*ifNjHR`>o%TFizwh7dIRiB>#pIUG~_|9?}lEt`T5YMr2Tl>p}SfU#+VOz)B%Ro zi6nMsh07;VmyuqU3}AINzB>b)IXA*EAa{=qF5#md9VRE18KGzKZ=PZ^@VZX-msH@K zJSN6?^oW*#6g+SR4MKx4#({oH)z5UP_)8Zr>E)RZ3V$4hp66rXE>!t>#xpX^zvfnr3f zHaHLZP$hROfgbvXvIm#S$wId5LfkWBv`FBeUv@%TJhGid4{_GIzvF8w;~&R2FD#35 zinq<(J?Kj!Q+bi>i6hm{CQP)lg+p^&sPo2v*u`DE2D>zf zQTnETl>M5P5mlLCZEm#UZ1#?ZlIRY#yH!Ey^K<@WZYquMyPqEAeflW1`Z`Bx0SK_m z=~7@8-A+7Ns#2>@wO>)pW^ZUH;Wj%lN*TUqRH>=3$PqPW9Af}}AVFe0vbw(FxuGEB z;yl*8;c?dIfLH6XmcYO?h_NpK6Ze*cH!z%%Xc%cG>$Lg3)@AMfNwzU<38xr6OA1Vu5&S$Aw!IaiuTdl`zadnPHK1M#siR0C@ev15ajPR5 z%9DeNk%pW;O5Y9fuEjVgNyXj!fF2<6yU)pUd)`_NWv-lG6tINH2a^@@8vt_Oc*sO_ z)3l;p{G>7`7Q_jh6+ir1c`>3pNlWh@InUqr1>K8A3=>RS2>E7?iQkdrGG!!G?z+0Q zJlwH{^udyN)CiTU$dT%u}Yk#s9t-A!NyC`g6-Q>4oFAe>8CK>8Dzmx^t|QCL7C{WIyZM9sw1(X2%6Cs zRdVH%eaSAn>VtMA(Q9Y5iPWSZ(_p^A(fwAnX{0{Z1}uOcl8G^A9T^YLnA=+~5g4EC zJ9yv8yC9GL-5a)n9PT3fjh=2vr7lcUSVe{F?Sd~tA3X2H2y)Ug8Wr*_s_wOW zvvsdN^{r-LWwly(ae<-x)?AO<-$8&thpm_b&cvUI9SLIOGU)2W|48M650sdw?XH z_QX~NrSxuwvUKxUY7&PQsa`NZ@SEs>YBE-Imdf_H4CeRzl^q&$bn{ z9PZ`xV0dpV-zvQU?9n41eqe0Na!Kf{;321Q;h7y1COH-QF=M@M?}<=m>C(1#Ou?K_ zCTR*M+qlS6P`HIjcgy(l)6PrR9jegv~q4H*{oXXB!^XjxiL=%=>Gm=tTnRU|B zvy))1M7k3*L*s69*OhxhNYfoF4#=nCPyeuSe)08etk1y7+pUmHMl~-WJY_@!5YA|% zJzk$uYCizCr*DWN+jw#i&}2c+IG7A~=_R6ZrL@_6 ziSS|^vY^*r*tuU5LpK|_r!v5JHlVSj!$?IAImRJM?)AceP)U+KctVw)?%oVum%C=k zQEagSR1S1>o_au^R%W0*8go|9+jp+SA&<`j*FW0BF7p>q{Di}#$GyE-2)7eMYViUL zU=CRm;n7S2{QM`|4W%yf{R-d@RWcH7AQkoY6alpj zw|6~SsPqBRr~nh1x?sbUGZ5@IjL(&i3k(N1`(o(P^X=(mVunR1rz8=2Z!PpLvuII! zuon4FN2&OJM?%W;k5t@EOX54BNv=IJil-%j zRD`DPMrWvopa-UR&9GnX5fG{=F!PAZ4cj7H6cuB#02P^Dhc!L3wr<-8a(*>He!@Vs zl#D~1ow$N~Ja!lQF-jcnf(ER6V*m1+MQ1?)?4D=WNZdr9Zd?TYFGO7=Ne0YIv$<=* z)3~HpdUFpD{C_zTqLbzC567J&N`+L(3OR3o>OJITD#h@8+^(a0vRZ`3JvJ2JxTJx(-24-+U&Ga5OszoqHij zV^sg@DD?Vzy(Ij+mMjE6eSQT>)?*-no+keHX*8}eQ3m1YEYLZ(4*?R*ZcPjn2`;jh z?iSg}DX;3s>lQ0Fk0&*|y?CoF}Lf>2Bv{M3B!@)Be?4saW38LGrtcwZ1-@5MWNx zOLrVWDHVNr5YYEY%#1kk@)4%$xKG#m!fathkg^43KcJIDBKq4_a<*%z*0ca z&19weQgX>gJNm|Ejcq2g1uHb|`?v8EzaFEEpDmu;7LqHPf6~z!BJps0akz*Dzd-^W zc_kN#du-7=|8}#;+TR;{CT`--pys#13xY1vf3jCj7B6hBw@R>0)J&?%xiZj*{YgGI z63McIC4m&cm!jL;(R}HL?C4TD9+RDf;LBrZi0kHXtXM@;ArgX)pAQkVpSYc>GCc4( z_C~FAwVn}x!^>-tqATpLQn0}>rnH&h@zJ&VH=iYZU!kfM zjyc4jUWOC zr5FW45e4ZWB`P2mihzPj^B`5aNH4J@{ol%&d34YtQVRhIa#>O*^Cywdx&HOg}&1lwdEw z1HO*OsKSO$e#bRkRsE|8I8`6^SPhvf63puQZnM$1^0exKlL-zVW4|?eY)eDsQ^X+CvUD>GUu*78O?FI9u`r3tWICoN>B{}3ub|YaT6r`4Ym5N2 zo`t{iIs0D7GZQe#M)vbQ$3$4-MbjI_ecm7~+^hw72kzBz$y<4Ry;t{(yKNx5oI&^F z4h`_*P@kzL>ARPhR%u#jO4izUl(>z-p;AkpOav_?Ct?B)dX?26HlBmfEt{$sD7YyKO2txT~$_k@q(7=fcN7>urMY>j0}_p>4*u$SxKiYA~B#F@;R-7m)I7A6dd(3hk2C z{HSC({igQ(PiEFo!%Mv1DcLa7#jkh*&UF%sRGPf$OF#h;L+$G#?t=*)7A)TI^`0R z{&U~#udJeSNX*fKrVVSWs|{rzwA`KzUbw0O%*Vek{r7G9&rAtyhAg>O{eNg411yU= zPj)|g(xC*!fyhYs<6ku;Gf)$mjegjKi8!Y`rl;1Jc?h>c=&6yLz`8I~n{TE!;ij1XnKaQw& zOd&7X!c@9Trk~&pW;s!Sh^A8_mf<%e{NcPe0?OymN zA@ENkRo!AzppF3a?Bs0Zp2x(?V65^7QnL>H0D5%IA_5_hVBo7^F2=~CJ^~azo(Dv{>PYAa)NyL+e$oNJ`jN~Zdagsz?_m9i zp{Iy27)!R0UJQrY$YJ^xCJ2<_L8gf~%iIIq`!6b}dd(wGnN?8>ayz*icvNOF^72$x z1F^_7s3T{5mh}(#Y+=^m_H(~*WD*UMz3MVl&&V-;}?OHeH{kAVoo(H!-F$p z`3O?E|NIPwL312LbUtP<9L>Am98Du(;An21S$8z8psb_JhLgu^e!nrsS7LI~8a3Z$ zoLj5=j&w^nSpb$_-mZh?_Md>|)beUVh0EPDV->bxRUiR>RWh>c$)B=+TV=M&#idd$ zZnTk=9daQXFpGa9+rLr#f5h1tzfyyZ)9Hrk1INllv19N^qKaz1sWvJ`C>+JB# z=H;&$=*cBqJFm03d$Tyk<}==Ft*8!p$puDT2=;Ck&#`8>$wA|}9h*g|D-Z~DLa_#W zQdY&_@_(Bre~qks^!)f2R*1`m20g-2M3PKGe1ttq#+Q)bD?XW_{{;Qmw~Kv1L310# z=_d$5h#KLK7|d*65^JsH`_3XoN~L7$*urDAN%{spk4e?n24O@l{N zPOzKMIKc2XNymD}9VQMmPLdp105}6m4UqjOUEBcNpRwb0f__5QZvc$c9P1W{i&ldn zq3#mCJi24FYX`VHEzcQ*`6s@^hF9=2NN4yw9k&h10xlb4uWLkbbOyVYdH`y#>LaLQ01;lG28H-8pHvztbm$LkKT^AbqDjQ2a|R1ZJyGr%%#DqZ6>xGp+I?` z$mDGTUYZigF;k7HC?fdw9D^30Zg4eu!90_4{C$v3+w%sQ-=mF5*WESkws~GaUoMX! zHXcM}{C>gPl4QC2o^1(+*x{6+GhkXNDyxti>Hny(Vk7=KgFS4N^hs$#=QYV->Y2%Jj1GXntwC%Ch{`Uc zHjiVEuk0agVla8-8tlj1NqO$qvpPBlo4fJ*3)f?~F;dR?Cs=zm67*vWrKcW31Ax(f zRr3;O@T6R5VYKb5uFOWrRG*MmJHS*#BF>H?w=)6-??g#l1Q$eoZvQEUc)uE~SIUHb z0W9^(8}QwCMu7Z*^Mqd9C+fw~wiV;Iku|#*Dx;+&lE%rLV27iJ-Y-d^4i9mHMA(}>94>l+>s2RBaOPaUNelMB*b>jd1gaK3 zEj=<=UrEv6kQ3T;#^Re~&jDnK2|VxtQ@nJJh#ZH1OMiVUPOs^L58>ifYo1n3_)RNa zPx-0byi70$_Ab9*V^A! znn8QZx^lVNGk1sE{l^Q25UH@Zh(|$9(y2{S#jjPbGIx8^aT%e>Ti9lyM|i;4&5M%6 zm74>LX!;cd95Gb;49ug*O~vi8%o{;BLCM_h#Bx~SyVS(b4YdTp^tXWy<(G zuCQOs8Clc{%KSsf5#D~9(X$+zq(_4`m!lPs_Pq9C zW3a$2y>VM9PH>lW@f%eW=I#z917<8Uar4IPqe*Oyu>0%c?ZSS)vb~Y`h(f6+c<{m{ z;vc;JoG*;`sKO>GZ1WCgQ5b2ptny*nn4+UB3beRKisyKL>`}3enJ)i*tR{29!|I3M zdX)r@be!i1MVelQWiw4ksR+_EvW-)7 zKX1RlWeLVp2m^xM?VJLx-*4GQ1GYbOIE^V1yvgQsG9F zE-vOG6d~<;0v>x%hBp-2`3Tifxj2^=I*PaP@RXl6VD`KD zYZEj)7*SsfUlB%=o6vmAPov+oKp?{h(Nen1ewFthw&29Gqja^EF{-)6#ja@H{+Qf{ z9@ms9R*U8-0c+moG;UY4^w#sha0GzK_qSS^lRMD#?diX+z*f_9XsDcs{hxo=@6w`= zL&O38vilW}aVv^X9=2C3xKa}XaWuOK3umu)X-HEO82XU{Urb)Dt5$cH&r>_LSw9>B zm!<3BPbgyX;%)AR_l-zU-kC438;!O|(28>CLFT*Eb{se&3xSZU({S;=*`gmR9IQL< zG)zkch-bW5E%QlU>vQLj1(>byD5*n32O%CGdhR@b@O#hvnVW6|wzY6{ZLd|FKQq=2 zz1Y)H;Y@kew@@44-O5Z4Gbh*4t1uP26Z77)K=w&1#(GOT>NII0Vsl@&3?+40p*|X9 z$fwg^*(5pf5qAX}T6#R6bJG9=Jb36$M=!QkMG96}JDrv1h;IGxAhdMC2r-vKet(Ib z5*0wiP>XiIh%IV|KrDq*rDm{Q+K8o?s=82nskKHQq4$?^WTR7OTPo6{ksL8b7j<(u zmt)jx)V0LJ8bhC&a6K22bZ?b8rs&FBsOWm$8tW-HO{!6vX`=@@)4!y1Q@$XEJpGpB zD|f~&v;x(Ifaa?|$nE?*XVE0=j zp9)GHmqdL_PVHEaVt-F|-a9KOTybrk;eSj1bb?X_CCs zesPG@|FA@Y<~maiUmTHie*xa^`0P-PvcgLVdMd(bXw964L@e=8%GfDxef0STdeGD3 zU>ghM0+-cZ{-(BofwoH}#5VeixISv4`HD*EXmP;I%o$|Aod1->l=G( z9+!}0^pPeOi%t0}t@Qa?*lPLW=eSae7~1jlskPp)q#AX+8&G7mgqN&|31bvrEm@44BWeNKAZ6d4V0(8SzWxWHDkm zit;rs4!-1!rNo=hBb{kObbKxP^=f}(X)Y?_oV3q@dNI%vw;n+wLUku+n+D~C)`5_~ zJ5SH-+$t~gYc!$^ALuzpcBWzIi4#*Kv4Gh=YVT6SLM=kZ`fzJcGk(1OjzSIqh>PmT zHvAYESknsj3iZ2Zc87%83$6y`3(iNiKQ-YNlitZ0PO0{>qqU%E%O!KkIVz}kTTVOXn9&)C;#ZTS(s?*JW4GjF$EANNe zQSVepb4rfQhg}h`vI>n!PSxFm&2uqV*nI^c5U-c|HQ0R5*A-N5L05xO4rF!Vcyt`L zRw!>Ups1>AeuvVy=lkQUj(49@!Ql`W1w!qce_ut(P-E51z0Jj%~DIFO?gmB}h# zW4WV39i@w?u8pErd45T(X$u(5@g}dfJ5}71vlu%Q>4k$pSTCp}J=G!t)FwW6ix5++ z`Y2l*Ej9%DMr;T?a^dJZqft%#P^6pfd0K#U*OaC ztaZ%t4~!jP?vnQG7{_Bf@gJP(iiLAqhua2e+u(~GrI$ziXKYH>QcK95hJ1+eu7Kkr zhhtc~7goHLx|x_E{A!|BW|y8jA8m3z({mK_eu5)^#@?48u9PJuf6!UG8(YpNCAN4+ zZjg2rJ~srPou9X-cOy(xJ|X7)%{lHxj9>4aKSH`yz{~(W(v7Bxezp*6>3b9vvI0Lt!Ae%(P|OLrae-kC{W)T z+yHbpqP?hH5%Bg3cvX$j}=;iEQ>ugLQ5l9HdkF?T1$uR$#3A{2tIHh&2S_O~Lqu=1t9Eq{vzBg2guR@LvBb?{B^l3wl@XR9{m z#1I^-OcGrP_NAm8!>Cy_ou_nJq7+Ms>sytU?0l*^>!?)o^_wz>NS%h)4vAzxSXnnR z%#w2p`S31ASMttAX2s@DyW95$;aazv z!p&HdPS-mzC0M_&QOk(cWwFwsp}06$lv3=RkdrqBCom0ABl0BDlS?~JX4i(1GU1u~ zZfZ;`vw>v`+p;%gqbF+4)U`|e zO3zCgVa6d~jXZ2b9m|Qz>U>62v7i%cwm>e3SoJzNIg3F%p6;B0x*ri~qR!5cvvt1^ z!VQ@D;p~-Zz-d2V)f)4P4m_82?(4dNhzj-e8Col1h!a8TqT}QZonNEj%~$i$VS5fo`H2FH_;j!a zt6g`V7}V0zT{N^ibnaHP=dPhP4Ttzkb}TXKr(!waa$WD*41r%VCYOT`7wLM`e4vtG zyOypun~pQ4PL-18`{-Z$$j0Wh;0F4FbEYR{o;Bcr^=swn`w&R~of4JMG8~u%Sk$CxzAd_U z{7MSENBmt)76#96nF4x9UvS64?d z6iQqiy%2o!nN&&~i6=7gMu9_)5UPSqwzM4BFbX`a# zSJDK#e!X4V2u+SoMa~6NLfxq+NBDeYCd>1Oh+1Hzl(?rw8lF=*XW&v;Z zJj)+<2P4rTN{W0j6`g%8hKAwehV8u6L0+=+wbu-ZDTYwA&hO%D0hPA#=n!^70jhj6xs$;giA z**WE|Z5^0h@1PG3`-N4D8%^fwj=`Q&3-#xvRmfzC(s@4k>R4*&^ax_D&pcq#Ms@Xb z=^Cq*dPfeKBmo+EK#u~xB!X55Uz+~_-(zrb`#0GVYVPr^ zVRsIgp7Q654@LEhXVD7lin`_G^zjEiM;`9^uw;||elEh=lUf%RJf_x#y@ceHOq%ee z5o+m+YVZX_DP^ROQf^LtK%@-xF*)sZIUoWZ+OX6$*hzJ@T^7eQECY9IHKkTWMc{?y z*V6O4>Mp!fb-m{pTDLd8Wl648v;c8i-H~!Z>*Xr4^vXdh98F!&gcI2j({z98gVKRi zix*AGy=S!eKYuf{qNI7Tukxw`C*`HuwOTA&1_RRBL~{*QYMvZih00C44aEqEsI0oc z>2xZ!bWW4DB##I7L#S`IE&lBVSl#6xCFS#s-^+7nKh`<0n&|9X5|f$5$`vDLcH&m{3mEKmz-hkAWIMbdTj>Mi<0HE1e)x#$o?@A*vfDmA`p{YW;IDw+ zgdHNGPJ;o3rt55b>)gRe#%4HM#&uE#nRi17_wHz*3 z>rgpO8e*ETF@8|&BCqL>R%ArGE@~k$@6S0;tkJAnlNUZZ67V(EOBqLqHr!b=XFCQtfqd*;mLP;F zW$?56fS*Z6_Rx!@HbEYrMY1L+dabPk%pt42$J|$FZH)cKS~beo(w%O9u^2q|eY0`O z3nDl&UGDO~XkYTbc(3&L{oDWI{o{D@STY?JaVl`)-s^Gj@oWg>tcH$y_Ni-k{~tTK BsT2SJ literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/defaults.parm new file mode 100644 index 0000000000..181f066cec --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/defaults.parm @@ -0,0 +1,5 @@ +BRD_HEAT_TARG 45 +BRD_HEAT_P 50 +BRD_HEAT_I 0.07 + +CAN_P1_DRIVER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef-bl.dat new file mode 100644 index 0000000000..0d6e8bb913 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef-bl.dat @@ -0,0 +1,79 @@ +# hw definition file for processing by chibios_hwdef.py +# for H743 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 7100 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +FLASH_BOOTLOADER_LOAD_KB 128 + +PI5 LED_RED OUTPUT OPENDRAIN HIGH # red +PI7 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue +PI6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PF7 UART7_TX UART7 NODMA + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define BOOTLOADER_DEBUG SD7 + +# support flashing from SD card: +# power enable pins +PG7 VDD_3V3_SD_CARD_EN OUTPUT LOW + +# FATFS support: +define CH_CFG_USE_MEMCORE 1 +define CH_CFG_USE_HEAP 1 +define CH_CFG_USE_SEMAPHORES 0 +define CH_CFG_USE_MUTEXES 1 +define CH_CFG_USE_DYNAMIC 1 +define CH_CFG_USE_WAITEXIT 1 +define CH_CFG_USE_REGISTRY 1 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +define FATFS_HAL_DEVICE SDCD1 + +DMA_PRIORITY SDMMC* + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 +define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1 + +# Add CS pins to ensure they are high in bootloader +PG10 IMU1_CS CS +PJ2 IMU2_CS CS +PI4 IMU3_CS CS +PE8 RM3100_CS CS +PE4 BAROMETER1_CS CS +PI9 BAROMETER2_CS CS +PK2 FRAM_CS CS +PE10 RESERVE_CS1 CS +PI14 RESERVE_CS2 CS +PI15 RESERVE_CS3 CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat new file mode 100644 index 0000000000..4fa315f3e8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/VUAV-V7pro/hwdef.dat @@ -0,0 +1,286 @@ +# hw definition file for processing by chibios_hwdef.py + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 7100 + +FLASH_SIZE_KB 2048 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART6 USART1 USART3 UART8 UART4 OTG2 UART7 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# UARTs +# USART2 is telem1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART6 is telem2 +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 +PG15 USART6_CTS USART6 +PG8 USART6_RTS USART6 + +# USART1 is GPS1 +PB15 USART1_RX USART1 NODMA +PB14 USART1_TX USART1 NODMA + +# UART3 is GPS2 +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 NODMA + +# SBUS, DSM port +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# RS232 +PH14 UART4_RX UART4 NODMA +PH13 UART4_TX UART4 NODMA + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PF7 UART7_TX UART7 NODMA + +# debug pins +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - sensors1 +PG11 SPI1_SCK SPI1 +PG9 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 - compass +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 + +# SPI4 - sensors2 - baro1 +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# SPI6 - sensors3 - baro2 +PG13 SPI6_SCK SPI6 +PB4 SPI6_MISO SPI6 +PG14 SPI6_MOSI SPI6 + +# SPI5 - FRAM +PK0 SPI5_SCK SPI5 +PJ11 SPI5_MISO SPI5 +PJ10 SPI5_MOSI SPI5 + +# sensor CS +PG10 IMU1_CS CS +PJ2 IMU2_CS CS +PI4 IMU3_CS CS +PE8 RM3100_CS CS +PE4 BAROMETER1_CS CS +PI9 BAROMETER2_CS CS +PK2 FRAM_CS CS + +# RESERVE CS +PE10 RESERVE_CS1 CS +PI14 RESERVE_CS2 CS +PI15 RESERVE_CS3 CS + +# drdy pins +PH4 DRDY1_ADIS16470 INPUT GPIO(93) +PH10 DRDY2_ICM42688 INPUT +PE9 DRDY3_RM3100 INPUT +PH5 DRDY4_ICM42688 INPUT + +# use GPIO(93) for data ready on ADIS16470 +define ADIS_DRDY_PIN 93 + +# I2C buses + +# I2C1 is on I2C1 port +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C2 on I2C2 port +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C3 is on GPS2 port +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4 is on GPS1 port +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C1 I2C2 I2C3 I2C4 + +NODMA I2C* +define STM32_I2C_USE_DMA FALSE +define HAL_I2C_INTERNAL_MASK 0 + +# enable pins +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PD11 VDD_5V_HIPOWER_EN OUTPUT LOW +PG4 VDD_5V_PERIPH_EN OUTPUT LOW + +PD10 VDD_5V_RC_EN OUTPUT HIGH +PG7 VDD_3V3_SD_CARD_EN OUTPUT LOW + +# PWM AUX channels +PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR +PB3 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PB10 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PK1 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PJ9 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) +PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58) +PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59) +PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) +PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61) +PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA +PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA + +# PWM output for buzzer +PE5 TIM15_CH1 TIM15 GPIO(77) ALARM + +# RC input +PB1 TIM3_CH4 TIM3 RCININT PULLDOWN LOW + +# analog in +PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PF11 BATT_CURRENT_SENS ADC1 SCALE(1) + +PA5 SPARE1_ADC1 ADC1 SCALE(1) +PA6 SPARE2_ADC1 ADC1 SCALE(2) + +PB0 RSSI_IN ADC1 SCALE(1) + +PC0 VDD_5V_SENS ADC1 SCALE(2) +PC2 SCALED_V3V3 ADC1 SCALE(2) + +PF12 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3) + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + +PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# GPIOs +PA8 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + +PG1 VDD_BRICK_nVALID INPUT PULLUP +PG2 VDD_BRICK2_nVALID INPUT PULLUP +PG0 VBUS_nVALID INPUT PULLUP +PJ3 VDD_5V_HIPOWER_nOC INPUT PULLUP +PJ4 VDD_5V_PERIPH_nOC INPUT PULLUP + +# SPI devices +SPIDEV adis16470 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 2*MHZ +SPIDEV imu1_res SPI1 DEVID2 RESERVE_CS1 MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI2 DEVID1 RM3100_CS MODE3 1*MHZ 1*MHZ +SPIDEV imu2 SPI4 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ +SPIDEV baro1 SPI4 DEVID2 BAROMETER1_CS MODE3 20*MHZ 20*MHZ +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV imu3 SPI6 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ +SPIDEV baro2 SPI6 DEVID2 BAROMETER2_CS MODE3 20*MHZ 20*MHZ + +# two baro +BARO MS56XX SPI:baro1 +BARO MS56XX SPI:baro2 + +# three IMUs +IMU ADIS1647x SPI:adis16470 ROTATION_PITCH_180_YAW_270 ADIS_DRDY_PIN +IMU Invensensev3 SPI:imu1_res ROTATION_PITCH_180_YAW_270 +IMU Invensensev3 SPI:imu2 ROTATION_PITCH_180_YAW_270 +IMU Invensensev3 SPI:imu3 ROTATION_PITCH_180 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# compasses + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# red LED marked as B/E +PI5 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) +PI6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) +PI7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) + +# setup for "pixracer" RGB LEDs +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 +PE2 LED_SAFETY OUTPUT +PI13 SAFETY_IN INPUT PULLDOWN + +# build ABIN for flash-from-bootloader support: +env BUILD_ABIN False + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +DMA_PRIORITY ADC* SPI1* TIM*UP* +DMA_NOSHARE SPI1* TIM*UP* + +# Enable Sagetech MXS ADSB transponder +define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED + +# define default battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_CURR_PIN 2 +define HAL_BATT_VOLT_PIN 16 +define HAL_BATT_CURR_SCALE 60.61 +define HAL_BATT_VOLT_SCALE 15.7 + +# setup the parameter for the ADC rssi +define BOARD_RSSI_ANA_PIN 9