From 3c390952715d64c48fe8e32000b3aeb8a6f85f68 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 5 May 2025 10:44:11 +1200 Subject: [PATCH] [Sponsored by Holybro] Support for Kakute H743-Wing (#24669) * hrt: Fix PPM input on channel 2 The CCMR1_PPM define for PPM input on channel 2 was incorrectly set to 2, which was setting bits for channel 1 instead of channel 2. This prevented PPM input from functioning properly on channel 2. Changed CCMR1_PPM for channel 2 from 2 to (1 << 8), which correctly configures the CC2S bits for input capture mode on TI2. This fixes an issue noted in the existing code comment: "FIXME! There is an interaction in the CCMR registers that prevents using Chan 1 as the timer and chan 2 as the PPM" Tested on STM32H743 with PPM input on PC7 (TIM8_CH2). * rc_input: enable sharing serial and PPM pin By setting RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX it is now possible to use the same pin on the STM32 for PPM input as well as serial input. * boards: Add support for Holybro KakuteH7-Wing --- .../holybro/kakuteh7-wing/bootloader.px4board | 3 + boards/holybro/kakuteh7-wing/default.px4board | 79 + .../holybro_kakuteh7-wing_bootloader.bin | Bin 0 -> 43324 bytes .../holybro/kakuteh7-wing/firmware.prototype | 13 + .../kakuteh7-wing/init/rc.board_defaults | 13 + .../kakuteh7-wing/init/rc.board_sensors | 20 + .../kakuteh7-wing/nuttx-config/Kconfig | 17 + .../nuttx-config/bootloader/defconfig | 91 + .../nuttx-config/include/board.h | 503 +++ .../nuttx-config/include/board_dma_map.h | 81 + .../kakuteh7-wing/nuttx-config/nsh/defconfig | 270 ++ .../nuttx-config/scripts/bootloader_script.ld | 215 ++ .../nuttx-config/scripts/script.ld | 228 ++ .../holybro/kakuteh7-wing/src/CMakeLists.txt | 74 + .../holybro/kakuteh7-wing/src/board_config.h | 270 ++ .../kakuteh7-wing/src/bootloader_main.c | 75 + boards/holybro/kakuteh7-wing/src/can.c | 132 + boards/holybro/kakuteh7-wing/src/hw_config.h | 128 + boards/holybro/kakuteh7-wing/src/i2c.cpp | 43 + boards/holybro/kakuteh7-wing/src/init.c | 276 ++ boards/holybro/kakuteh7-wing/src/led.c | 235 ++ boards/holybro/kakuteh7-wing/src/sdio.c | 177 ++ boards/holybro/kakuteh7-wing/src/spi.cpp | 52 + .../kakuteh7-wing/src/timer_config.cpp | 64 + boards/holybro/kakuteh7-wing/src/usb.c | 105 + .../holybro_kakuteh7-wing_bootloader.hex | 2712 +++++++++++++++++ docs/en/SUMMARY.md | 1 + docs/en/_sidebar.md | 1 + docs/en/flight_controller/kakuteh7-wing.md | 86 + .../nuttx/src/px4/stm/stm32_common/hrt/hrt.c | 10 +- src/drivers/rc_input/RCInput.cpp | 30 + 31 files changed, 5998 insertions(+), 6 deletions(-) create mode 100644 boards/holybro/kakuteh7-wing/bootloader.px4board create mode 100644 boards/holybro/kakuteh7-wing/default.px4board create mode 100755 boards/holybro/kakuteh7-wing/extras/holybro_kakuteh7-wing_bootloader.bin create mode 100644 boards/holybro/kakuteh7-wing/firmware.prototype create mode 100644 boards/holybro/kakuteh7-wing/init/rc.board_defaults create mode 100644 boards/holybro/kakuteh7-wing/init/rc.board_sensors create mode 100644 boards/holybro/kakuteh7-wing/nuttx-config/Kconfig create mode 100644 boards/holybro/kakuteh7-wing/nuttx-config/bootloader/defconfig create mode 100644 boards/holybro/kakuteh7-wing/nuttx-config/include/board.h create mode 100644 boards/holybro/kakuteh7-wing/nuttx-config/include/board_dma_map.h create mode 100644 boards/holybro/kakuteh7-wing/nuttx-config/nsh/defconfig create mode 100644 boards/holybro/kakuteh7-wing/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld create mode 100644 boards/holybro/kakuteh7-wing/src/CMakeLists.txt create mode 100644 boards/holybro/kakuteh7-wing/src/board_config.h create mode 100644 boards/holybro/kakuteh7-wing/src/bootloader_main.c create mode 100644 boards/holybro/kakuteh7-wing/src/can.c create mode 100644 boards/holybro/kakuteh7-wing/src/hw_config.h create mode 100644 boards/holybro/kakuteh7-wing/src/i2c.cpp create mode 100644 boards/holybro/kakuteh7-wing/src/init.c create mode 100644 boards/holybro/kakuteh7-wing/src/led.c create mode 100644 boards/holybro/kakuteh7-wing/src/sdio.c create mode 100644 boards/holybro/kakuteh7-wing/src/spi.cpp create mode 100644 boards/holybro/kakuteh7-wing/src/timer_config.cpp create mode 100644 boards/holybro/kakuteh7-wing/src/usb.c create mode 100644 docs/assets/flight_controller/kakuteh7-wing/holybro_kakuteh7-wing_bootloader.hex create mode 100644 docs/en/flight_controller/kakuteh7-wing.md diff --git a/boards/holybro/kakuteh7-wing/bootloader.px4board b/boards/holybro/kakuteh7-wing/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/holybro/kakuteh7-wing/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/holybro/kakuteh7-wing/default.px4board b/boards/holybro/kakuteh7-wing/default.px4board new file mode 100644 index 0000000000..f8440af002 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/default.px4board @@ -0,0 +1,79 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_BAROMETER_GOERTEK_SPA06=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_OSD_ATXXXX=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=7 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/holybro/kakuteh7-wing/extras/holybro_kakuteh7-wing_bootloader.bin b/boards/holybro/kakuteh7-wing/extras/holybro_kakuteh7-wing_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..190ceeaf5ab26369b6ec89a30bed57fc7210b6b3 GIT binary patch literal 43324 zcmeFZdw5e-+BdxRA<0f#XnH`>12l(%ZBryr)FL{Dr0gDowtzmv!O=j$XO}uq0UcBZ zQi@tcXOQ9y&~Zf28Aeo^Lgt}hZ3T369G@ovI&YymR8Rsf>JBYr_n7au5~?%myzlq@ z_xj_rK{; zxyQ?VJnQ?WM_c`ZxLjm|68lY0Ld|$t7a!L$=_}oHTN@@_9xSa8&na0xBCqdnxHMQA zecNzF_ngg2zmIEi_XxG_9&K$+PeN@~p}>($!8_hLzUXZFd*c&RO)|&swAZ!}6EPCm zJDB23{lS}?iiun|K;)bIh+N)J% zM_`D2a*)Vr`0n#T(o&F&`WceR<3g7+^Y;X>?B zAw6wwn%a8)$Nh-&l%mfx^;Ru0$?>dR7Eq@?^OTZ~XPryzvJLm?-`)4RmqhRJja&tI z`kulY{^{P3xuE2@l9f3h|JKNVekOa3Og*mHGVjN;T)>k|yS#7iailcAl^JNGX#&zB zw1{MGBlJmJmR(k(hPW)WGRxj;v!k|1ek(uFb{8P|tQV0xrSxW&$_+E^G7IS5Oh4+d z1Ap&D>e6Rz15AF2$(Z0erRdO74O-3tQkR*FGIW`&oX_fW`uwMq`_OOOTzfA;+wMc# z=F|ICxL&E-Ck$V&Fr$+AqFXO#T-&6QVd5QQwF$$tHO+3KVGc(2oNDHyC^Oeajl0=)0%wRdqWR_uSg%&~# zWUkJeGn*I~(`kI=kQwd-(uvOFieNmU==cdvJkLzBIb>brjmddJ$(=@FDV=@q0`kji*Z zYm$-w0?)oc+KaSznyxw858@_s{_~sRE<(agRblvw^$_OcCSrD*zUk4`torjt%&?js zT`i^jo19}yKpXi9wOp_Jv9%s%N`gDF_A$>f4>8mCUo>t4^idCQu)ag&dk@d?Fw?&Z zkeqLPm;tLbC71*GjQMhaOuFbpe^;}SC!GQ7J5_}gr*s~p_Km3B7_GhfM(vtnKfa~k zyoZz+d1s3IR3n}J;m{u<<3Yc*dT+FSLiFpWZ+y*3<}QZ0&=})jUGy7kbNI@}24YGt zZn*a3hS+vuvR}=avotFKxtJ_H{)MA-+3sskR$UHY^z)dyYk}xf=Ch^w zU*33jJ@V|}wG|tfj+p$<{sr0-8v*-GSVO18x8Aadg3c8h($Pa*Whm~Z1sW%m?tt8w6$ zxD4awF-axSelB&`6+W#F&^jkE>55|wsV*Y_xu2Lu7jp(8d-_p|>7jRWfxkY^qBMBzeiVa5H`cF2<4S>I-09i}d%Dk~`^?l64ndC&>@y9k2$No1o!3_^3vO3q2kj9HoBDp{!j$F$ue>$3h_?YU3X zpFF5>-rma>{sf7HK)q0}kP34iTAGn0H8X^q$Xgbr6{wy||}l^pnn0 zmqyF<`N)-^Ff$0QJwb;3clk+|<&3NxO^4@_lCc}to?sT6l@mI9PWj#ErCr-%|8Xf+ zo}=(HY`7+NdM@e7Zd^v>@{!9Y>By}`ZY>#$oPwM}5^0V>ju}OB9CDmMa~k9{9L>ce z7vFqI&S0_rkQ^}W=8+aMcl`UiXutoz^e-#t)(+Z7)R|#W*cqi=NsgsG8IIDfn8C(dosk*uCawuPex&Bm%gZ?C!?seE2VgOPeyTRS87RRPew^; zSDN#Yo(v~#e`#0xY?S$N6lb5DrTyV^e%nFuHBuK%_XK(NNMNLY|GUxPbHdlx9-!aT zaYI|pBjrTLk!LY4i4AmKhD-1=@_!95m?@wMgWx4HQRsio0LgLqbTSjqiPL?|9h}0X zF**5XWbe!_X2S0^Z#7zc>>Xx>UBu<+&pe=+)uj?|YDvyW799#-X%e|^K2DR9)P7!A zDQh&E0oHz}jmt3?Y--`}pb$(BdnWol>q)7So8RnaHNqW#xlA6u5a4qD-Yy52oDcme zRZJ(z8SqyXVpWl~hlv5HQ4kq9_6RSV!TXsaM*is$(xQ!H3FU=%&SuPa-t)YP4_2uy zRW)8>G++kr40C3^>GoptFRbG2&f7~*Tvp|&%@=AoxozmyVuSb-7bkZN;ibbDk?tVl1;hvr2Bl$-R9!PCcIRE<@3)8;C3n?3KnBbx04n z7PUJ(VdTk!gMmD05oyHy*JJ)4!es#8m^q3FI^<8_ z`WvnWT&=j?#C3l%5mr7;1ZEuNZ{QiB1!0xbcKu2FQX|>UqrGPogGl)sY00i9!Xqe; z!l|6#@k@qpz;u2KQ!$zd>j3k5R+U#J#)+xz;A_u-uYGUDPj3o`emZ0lHM51H>y0+$ zRvYPlpV(c`fCpnln^($X$N>5=GoA>S(9YMh1aDlswq&kiwJ!3o-L33gX-A>jnJVFO z3C+Z$a$XOliu4-_KhjtFy+GxLAK|UHfwzW3wZqS%y((v#Wbvp<5~akZ)aRM0shc8n z)k4dmyfn$F^QKD2Jc)qY-$dn*@As&&&tN4M?We??v?&Hq^O~aa5;5qSnHlwsNt=k} zn*W;sBYXRUfst|#qwFg0GYu;7dBbS&lgs>6PW~T-7kwUL{Gf(=F>WXOV(d=l#h9I+ z;T?G~TO@Lxq8hI{3&}u!L&*}=4OPts@k@!wzvv4ER?4xe-av*|{X4QP2IVo+h&ct+ z{z;g}7-o1izhk$nfA`5{GA&7r5m{q6)Eaq{(&e7QXExM|D)B{e zikKmOrey6VphbTC9UZ7w=F~)P$6Z{d;B8n6)X&v=Ws_vS#_ijn9JifIl+5lbMtt9d2PJFw?Vb^AuwP*IhmOXpqED_W!p+ zY~jW)U4KQ16rQQS-uSX&H7pQ0!^Aao)p>XgILY)2Tg-Afm*n7s1?+_y@J_USlak)R z$Pf01Lmv*01&86}{oo?zUxY)x;rWpB(6e7Nw=&kZ0|`>8OyWj4i%EhjRYJQ7+kJA? zJKam-`3_b-5dILgZx56yxg;*g#HC8_Nz5HFwpoga1VI0Ee!qr`&Tl%;r#UI6NOp3| zW^t#e5lQA4u~^ibs;nG%dXf07QfuSn#|OmpdyeLc?6iDQ-MxunT924F$y_Gp!7FQwQ!VXrGnlCx#M*k2@lrl>WmN?UU^) zqrYE)>YU~Cak71Yu|8F)F8ICurjyLHf>}ZTN?A=V2b>CDdcVSFfRn$-$&&}FMP{c# z)CL(XC-Vcd3w)sMg`|yAI5`=31#?z6q7Qsemto}l`l54B*PQQ7a;8fcws6p~SPSbj zfTH$;12YD+DxpJKD9u$2R%g?NEw5KZVFZ7IxUVoAdS;NZ*4n@EGX^EVfD$?RD@BRS zTV8|);r*hKa~efG=H31Q11SGD3Z2tBuinVx?i(LghA$_zYwY(qYaB?%9H}dx3?f{W@ z93}E^j)t!gGhf0N+m$>WllKQpzdszZ9ie=a^2>ZLFX|7rN(~;&Dypr0Pv44jk_l-N zGlR3m77@v&n9HKN+TO|}55>eoSPjCVH^a2n1;fOUkF{fD%~8B##T2I+E5kS`94Z)! z_f$SI!*!b0R6|S=p1N_>pQ&EB5n3sGOM;KPCE3T^lI&mph*64hkj&*vJ0hAPkrSXr z=M5P|rP(Mge}qck-vmt3SHRd9{tD&+9S^K!LN-4G6q9(v>v%1?R+zi{w2ZhIzH zpk#clf_}yABXX7ENM}TykJ-xYqfR6V+wmG2FY&^2p`^P|2W(d1RdT>-}OmB0Ct&c@0+f%|+d zbZ1=oSdp1bBWRhG&qFU^rWtZW(5S-GXw7ugNpQA`zP%${*2D+zi{z(;^P2!O^~B`_ zI+F6+gOC;F{eyBK`h_k6WejIE=}`_Vr-$`T6mH|d)j&A(+i-6Ha`MbkqINAWW*;oD zvhr(TCQBo(r|qYb!T0)U-f+E9ZAtWJujPY9gks0#u}B8-!m>)q{4g=^T}tGo;fS0t z@lYpCUz4)eqAW_O6!)-dP~20i#@>n~kN$~TyWl_BNG%J#6@*SSSp;rd*MeUDaTWt~i z-^cHv;fMNbm0J46WWmRr#f(y0MXXQN;AHCm6)N8o{I<&urdj;eB?5aO+M$4YX_@3Xw{q|gABCLloKDrvS^1&gd zo^!GF<(o8-^|VY>ZKGwXc2OK(@qNBUwQXiEdGzy|nW*azL#LI32CwAoQmK|Lr6sJE z)WJALwafa{jzU@^ze|Oh>3pVjQl7+bn<<{(ViirO^?c2eNA9<6?22W_*q-i+MH#I8 z%#f-+%Ap`z4OxMYF$24y?T4?ZAVa2u>wQGIyPViZXJ|Nd@(ATqf|qqNhBUk_>5JaG zB?IQlXwc*77FZmij|kO!o9BE02?bU@#J0m^xQh}!rd?{?BM|KSf%>VEo%@T|Od=sT`O zT4=o(L&q}`*1&s8WmaprZMXPzgB4ibH&iLD_Do*O{E3)8QR24dQ@IqDLLxuYH(jI< zzZ_zw3Ae`Pc0qbj(Q&Jx<>|b~xA0<`YRu_7n%q*B$AR^Z_2&XBuYhk8IX1G+tR1AQ z&F-NKTO7Tl{6dWmJQSQvHsCGAFp>8irkpPy^Unl{1>78d16EELB8DqiHKS{@&U*qp z22$&duUL8TNT!v@%Z?DU#>r7@%=_^Gvx}J3M#i9)-yeXTXP4T@BHuDV3{grB zU*V`UTK&V7Af`koxje)&xQ#zvgIf4}D&NzM19B zzSm_qewh?xIqCn+H~v3Bp5C)^Zof(_@{piQllxefsK0dz=<3e{2karg3nM?SpBLxT zw<`ALvG?Bmm_gJ}qY$qTybcH(AmVO7*i__Z-Mu%jHi)_i#P)9?2Ku69*ieS>PY^W` z2&Gw%HP(PDi>|e}=$iZQu+J6K+4k@Noo!UNrr%O2eT-OEl7ZC`UWta$VuvE^=Fia4 zh)U8ko2H9ppwhP?l`Lzz=_oN=4G>GOKNfa~pf4QydWd9w<-Zu1F3!iC_-x1uF2I=H zzf8<5B*cq>Tu(V{%6p|s*9GZ%0M85Fbae!7m7wqVbD+V|uR4cR;?qqe*9TcSCa7b8 zJIIvb(5~=b0>l)B`R}2x0;ee_sR5^sC3S?Z;TY8|H%8Tfl~g}K>UlBB3CldRBn|YV zulkp{R!e(b2c-+HR{~|gds$y{F)y}8BtVq1Ia9V+~^RG-#`4R`&IiT`|Sm z?M!{IKUylSpHS{x8~vshIYE3cBBN7$67%iejS@pwj;Ft`t#7Z$ZHmqmW(T#f8=qkI zvGVkROzA4*no+Rv+C0Od-f(6`vd6q`zn$|BhlU{0<~L_b*8<@yiQwgFlEagLp6>1M zY|<4)<*k>GMCkknGJ~dwj`y$n>3Bm@LcdQdf(P^MFWF z)1=D*9=*@(ze*);5`;t*{)Y{C&-ccO8mCH}r%cgt-6y!TCpt7-8`eQ3_ZRuitURH= zKadOlu5z*)bl!Q&R2^OSt^EYLFr5qZoz5F8vFi?c(${Ubt4}VJmNd0qCR69T1XogL z8pep;>0Cw7uHrhQ`T4NCmq;Wh=*NBDdzT4epn1`C_jYgMJ-JeDWUN;9GvL$K=6JNc zq8~b7QiWK0J+A64*aluuSR3;aC;xGnfmT***8t|H{TBmjr1P+5pNFhpMCocT5zM&m z#q|O%9#SOdIv&)`vX$|j$5FL%yUZg!Ddi2OG<>9t|Kj28}GBa`95a38#8 zLwW$Id$LV_%iY>TV9WU+%)rj}W0EkNZIgfJPVTKLJ<-Ei$NJ2gQaN7hY=KVCImA*q zGp=&y)ltG zIj&|76Ab_4-5?V`svTu6^Ijt>9X{_h+e*9d^=t0sXM;pFt2;(@P*U}4uQ3J+8Hcuz zenFnq6{qro!%S{}T{WqVb1>PfT}i$Rs)ROPj^j(aYPom=A8aV#6_v}S83AfCSuUYj}1n+-4FQ6aG?2;VAIIU-ii8rsO%Vmogv{K=Ecd98n#4c zCuAP*?`gxMXn7trwdgudG*0uxz3=v!I=KRt=mxpjB58t;kTWYHs|_TlKOUy# zQ5$7Mp7+*N#=#nxAl5fgJ%9D^zVdyQ4IU=tQn^vqFxu3La?q;My@eRy5uVpwli%#9 z+-tw$Bl7(UwfF`6=L6KccQv4$EqKjTWBw7ltXl5uGfV9&h|ET8DvStUgqNIy)-VA7 zSBcv!6f-lZk8i-QhK)SpvyxX0P)soLk#}gU#y9W2^$&tyzBgv}1mNKz#p)5zUz4Zn zVN;~P`ORiY73ppBrF`^tN~Eu}pHzNyR~kGQwsi1J8zYAxTf#Rz4|Y8BiOZw&%FC%; zNi(IUk{8i$)l(iv<$n9b9JRR` zQpAzogs)I5dFHSu}gz z+rr2k6Arx^&Mn9iGi43GIPHVWqwjwdBf`N)SOqz1tM|mXng;rg959JbG)*7ZWY21u zPW!;6q-vZ-lwd4)&d&SeZf_R1HZujm0I)pc8t9wilk(DhFPZS3#EY{Ye){3}A70#~ z2c_Dser?`;^=m_UIj}=0HlgFR*eXw(vc=uO(_CkzzM%8r;ZSG)h04X1=U2oQB)Q5f z&aW^de&U$2$qE@_)rA%CTpL!(H?bF1>{=q5=>6ZyF05Dx37zs%o!7B~7rCQp7{iVB zasJfVW+|zOuDL?t-r#9+>~czy!FAe{0_^`5)WZc&!xx)aVwR38n+$H#LddS}RkRLW z^UQ}&o8DVd{qU>!j<#z<--Q)Xcy$S_m%`JUFRb|DTRZ*co2gzk3bsVq{Q8Qhr?`BD zL5ymNKh%$iIZG^m7~?SUzP0_x-s6=Ks2|wNcCLt#5Z6RlnNbO@fBgKR6^{x`cOl~$xE@@Zea9JQ z3ba;Rv0wnqt`$1ht`&Y)o$?<#a|x5pb`dtuZ|`kgQm6csXtP+KkY)8hagfI1pj_9E z6?Mvd*G$RSYnwCL108zK%*e9^u4?-1(ea)KSJLP1N2^^qj`|f}G^V%u9RB8b<*pTF%MU7Z4Yn@U z-r5-BBBs5#qgqL8wD&*Yg$+uXb-KqP8<;P^i5G^WvbDK)>!U_syf<*XvVKK-MQe{u zS5-*!JD2>QN}K6%bg|6lMq1v~k@93WbM4!*T2U6Y{r#+h$`U*6S1MIL&$a3e*}j#s zo?zDJ%=T?p{=+)pVJwJ{cr>o1w3n=gl;GH|%-88eYL&MciILtf(9t_s{%6vAhiv8Q zT%Z4(k&lOo;Y=V!{30;*U>)Kjtc*3==qDED?BbP|JxM5atS_mTY)EclAm?vFZFQ1P zJl^9@+N8`!z9W8zoyK!Cbb;` zm2XzZw^8f!qVOR+OI54sQ)`-38Jq?aY-)5{F+imHYxX6F{V1kCKs^txp%{P&`l?vs8qqXb04)9 zKI=B+L0|vp$f_wK)t^Zu!#&KQf9Zy(yTA_*LT)W|6TwK21u>N>YtIE*SDUo%qp5t8k;~&EkQc}I6 zuzdZp$bEkE?N||8r5Mre;iN;#gF5n}QG8kAgX6e;g(QnRYhLF7_RMRjWW7@6$@PHj z<<}P+OcIweV@khVa0@@?^xIt0y+tjvWcRXLYype^QtI+ii}mGq)Io7wT6lAbR&8%48t8a#r;3O1tjgb}7=>-26_^sUMF zmUhh^+q}TSk3GGgOK?W(vcPKkZCzc@V>F}n9sQU3$a==CE~&8*1EPZTu{0hizq6TW zX&rfkv<}Dm=W09DAFZXUEYk+tZA&=x0%X0J>)G`mL(aD+&TbK$TIXg>QURn4#3L3( z_*tsUv3@16=y*IL@3lnAMB5p81DvHdc>VYME6?b!t^3HM&Nj6}KkR3M*)~5k#ovi> z{ak3e{ayGdCUlKfebIPr4drm@MyJE%apma?5d%1s=F{ zi+g5r+#1@O8>M~E<}MWZ6h42Z$1Jm4D{|42D7*tts4PLtq465dCV0yXpaR%c^d3E| zazmm29){fovPu=j&5w8oxOHdM32m{nA-m^yXyV#VEBt(wVHT)w0@l0}sE?8R6r}U7 zH;%*-(E6&p&h<1NVUZ^8w5eiYlX-n=(IO^g{!E!HPAMy2zocg)D8H)NUz-BiHXM@R zExS;gc<;jT2?eJ0o`Ig=T*m3xy1>!(o+B2q#V#A?sGDP6zld2l-!Aj^g(!o@=9NEg zUQaA%{gvy~rX@X^q{=m*R*bif(rebn2K8sKiWT#DG13k@v#tMA8iz=9g3apXAP1(7 zOH18pC!bm&^BwQeOkfrMPFCR_Kz7Q}5@Xgd(` zYe9(-9K-DH(wS8yNsCp^go=;UkY#7|`#Hl;)IIL{{->S z(P$YICg00}Z;TQh9>@9)@Nu%<4N3ES*j$kYPY;bP=!2F-vG&POFDUH>Re#T~vr_(f zWL<8LtfQ3sS9u-ldGR0WJKMPRKPg_sESf)#pVo%2f6U&zel9a_z8RdtA#ZieE6Xe4 z)-Pb#Zby<{a%%?Lw#@&kkwKSG7K)^yf_X0!}85 zZ3jQ7y>I-qfd&Tuh4jOym=sMwGZW(*8(BkMSSlvBm)_Q)uO6F8c8D`Sn1%f{j zeGuk`f(%`J^&U*n*jP zOqrJdm%uo&JCL_IN1TH7ETsVQK=`{kYHoUJohmXzpIS3@b5HG17F~Qp)N>c@dUnA%-zl5X(hx!Z9*qOMN?-} z+2j~<;n2;)osu4_uu<$l{L`>G_ufgRWCC>Rm{K`idtr_FG3|h=$SVE?F&dQKknUk_ z4Tr`J?@*qws)Hv;gbL-^oZjAM%Eet=S$ zNko)wR;&r}%UR$y*dai&OufTPz-_W@Ci8RV-YUpXJZIj>n$4@iq1y&+;O3g5aA*Kp zxr}Iv{jlp%`u4@aE&kvY}8?ABBzB7a}u^ zj;H{7fK(PKpUxlqdQLp4W=Vq z{UhN}TUd$su^sE6g~~E#u-N2{ZgOqgV=HBmp;GlDLo~++T_hZOcxXHDNZ0*M zNVfya(fkuu;0j}zrb-*-=(Wu=Z!G_1lI)6C`S{=%a1VI@2Bvo&QpQ#tQc`q>lr%$p z|Fgr}m77|H#+w@73C6`wY>&Sx2=kR(nY7$<8~m!b6X9n_AG(naA)T2Yy^4|kC$2AV zjb6(DXILj{_%=3&^^aGRwy_6CBscTA4$Vz%+m*G}Eb;m1+=UFYu#C2yVt7-8QnJD$ z@Zr$0K?0fhK`X|$nv*j)#**WMRoX`^r~M@Rq#qW^Bd z_T%tf#;f5YWJ|khxY;ePJSwx83l>pHlq>%QeEh$FY#G7F@gYy(KY#JZUtAB+mjAJh zy< ztmW=r!vRyt=f8xn2zw`n%N<=z(lO-6J5A3e*{Hs=akY8lhCm0(h&}MhMdP|sl&U`P z58QJH9)$gJLvQ$P2K^p<``wGCb#w4G^fs-r_w8tn^4lYHIowCGHuPS3+xT3#QBx9Q z%kbEH*;S^E=PyEwU)3KNStkbMa5#huysPx-hI2|oV~3J#>rnIt>@La!&964wl5J-B zayfJ^GxW06bUu8nB*WLb-#vkgZv(8p-^w% zCCT7nrMVR`o@{Yzp-~mnR#W_8gtMkqaGo8ADBb|wth4XDdO_Qh&T-3Cu$DIk)$wyb zRrSh=jS(ySZ>k$3R`}gW-IHhe-|vYTLnh7iol{z?()o;7C13Ra z20Vl{<%`R)iavwc|=wu=+=i15xpl*){fu~=7% z71mn0&W>3pb1qAgzfGBDTzK>))InwDr;*Y;);mUpn5h5iuY`s`&Bls<|jEZ1p;lNAaw<9__e z*Fn$H10SO)?_lIAW@gvu1ZZ6PoHhH`+@WFH1T!st022F5^f?@wJfMp_$ybkVsVQ4b>KG*Z%6eN zy4#Uh_FYW5M=+{_V?gas^}Ww_3Fd$kLxDH zXu=GcsXS(g6SG$hh7JuqW-y8-aVRuP8RrZesN{CN5j&)`xMHzS6loUHBBVt~C8QG4 zTBNl|_aWVf^h2Z{#==JFf`kXTFB#V~TaF@qAlB%%5_UYZIx?i&qvx!ar^5M z#d}hT%QwqpHE16r5QljYm%o4+Xxm(5yLmYDtG?Qz;n0@Ie{J8h_l858!_Q(DLGLQ+ zGZ_r|hc^|oA}2zQjk7DRG)A<$hE2!Tu#XW_+yI-Lp7-F=lx2KytqL-UtpF1ABUPsx znW;6(1Gc5|240g>qZHX5S-Y}_!JEBGN!0~EF{j^bn{c+VRmoi3s#p`!t!~9&bSrU2 z%>b9k=7;Xti?|6&YZqJ` zAU+u|SHKF}!Q2({n=2fc>*mG(;kT-@i=dq-r4D9MM7*<8K^(h|3KNpT*m z98>7O5c!Xb{OcnB$&r6OcxJpp;}$>@fYZ$nW0z|3{98&+DAVSjz-l=O`%}~B>m@@T z$vTA92mH_APz-SnMfZS1(WlqhW&Z^1p$i)_i_5UX&f*CRzGm-B4-W$|ud}&O9F8{=3 zW-P_+tJ1x$y+MI-C_>zxpg`_%bz-NdT@fCbrwDhRm+~C*Ko2yIn&Jm-Jj?{+xjonR ztfHk>dGFKf5lOxWGiRLmMJjh~&*OukDMK9McMUALw)@dNK^@t(ST|Ld*S`2U#5d9C zWexU`j!5(o;>qZ~B19gIM2xp7He*Ml$@RWsn@PQNRn7OohV~k8O{KpA zo786T(4 zms&Nt)2A-8x@wo!(=L7JN{PS=1$x&UiF)-I#~fEmWUZ|Rj+-x0f9)FBMbu(EjpF-} z2zO%gp`{(*P&OlNFUg$_-Q!lDCOB3#L5^1)uupEM-up>mFYq$;BwaODgw@?dx2a;# zW0LktZ`iX>otNrdv7YnNS(jOwpBA4Lcg9?>IK?&R9@hldNI$INLRUC+Yq(qzB0JY9 zE@;V_@Z%`W6JSxWin+L-9exMc{v?nt{x^2AQc3icFtyJj?$J0H8iqDS_Xg3Kv$J3D zBwI0aiUtGkVBWy8>57F{RzO@%RiRVTyZQr&;t{ua+@2c5V5dqkt`fvLYQdMCfUtOI z6j7bM-;Y?%!&QYGc3`DStcz{3!`qkY(u-AvF%l=u^*BBBJIG+{n3fc&$i=u=SM)ut z(g+)|J;(;v!}mB~(?I+qKd>_!z+ZD z#EVwMnx9r6=Zqs0iEKiS50()kkBj7fhn!x)i34R5U=K%(x?%;-@G1q?dX1)yf%JkM zj>>Ia26a}8TAUcM&c39GusX2NE=0)b9}V-;Qai2j&&n48zTmdh zcn`Vd%TFsSCKhxrK4d@b>#kUs-nBScVJxXt*8?Q;QedSl@c$jKdN(7cd=%yN`=BMt zAAqA0d5w}SGP~%WkB9qIuv-)PIq*g;c%9%K3T*<9qwBtax%>RP0wO&a6XJ=Dxo8PX zSJGRtcP3~h%Mk4_E04%`DtvGqIia}AuumKL50U>{Sv02P7DOKNVy<;4v;fg8tKZ;m;@_R?ZE7AM6~!w+iyYJ={WQ9PDLeNfWILTRwe;){G7Zt%#GKa z4TsW)If=Ji^F43r@h!4jni%t!E~eA`9Fu3>SQUw*<`EH%d&_9dS$s{*8)=P@f8;%A zi3)h4Hedxi9L*c4pO#dFLxbMb~r_sziMd-* z?(u+9G$rt3Z_qgPElFZcWOi~>z!98uFZ;nFBJ9Uic^?t%n?WoCe%M~bRFTO`SWB|| z{kl{d2f!BaqI3LKyWmSwm<;TTP9xbNe`4xjXcP8NQJ>UkNJ3WcsmtWP=fT6?Ut9wX z!#$6#$SIC$%vx*npX{vvy~Rc`7+|Ifc^NsEa0gj#&gDQYWQ*1c%vdkhwLf9+97gKR z7Ip{K&1qZ{>?Jc}?!ms3rkL3=_r{iO~VaZw8!R-hS2?bl8@X7!xhQ5X!g zg5O$k4h_8sgd>`2yx?D^Sj1=1n4j<090^W{$KH-S zw$36&c4pr8F``)}d|rnw_Pf&QTXtK}2c9d$m1x$)Vk(1Jb5Hu>))#? zYC$WPj+98&{1$H{ym5W|hOD7=xtBhNH&yX$OD5{2Psp0uz#GA3=WpjID((>f&@E`S-GW+=SyRz;r$};b^5Km?DL5mt^(QWt%9FIm z5cg-%wglolhUp(QS|nP_mx1GrpDBjjOr6Wg>`J$%`IAK9Pkdf%0kbp314>D;X6O1+ zgM9og9ouH*o~2Yn`_6VS^}A+eosB^&nfkrmf?$TlkE{E0OHNnUYL%JEqpc>O?ZZgN z`UIR)kyLQheyAm!N^VY;wejix86xb_JB!A@*T}s17w86DFr43kHWHyda9&;1!sJ~H zP+ahJTMK!d3zP#{_c}0=A$}htW_XmFM7~oS3{SU4uxF7d423Qg>0ZIPXVI=FJ`57> zjczT=c@~G+n11#P*le1D;k!BiEs+wr-~V-1 ztp8a_hqEk_@oaK0d5Df?a?32^GQ{i9G2%O>L|S-8J*n-lK@u~`7#(k`@kme`KjG8p z9gkMW1g*@T0JDqIR>`c|7Hu$}rIx4dEmq_50@%#@YFiSOr1Twye+hKLqr=?xL4elI zf)d{gSd1qF%#=5RF)<%C`U4+hwlKn|ph1hdG~)&A>NRQN+d!54>{+AyV!^?S%-tjO zT{!EtZjJhS`!|7iQj`E~PYNg(R^Q2&e9YY!F?*NB^Sy?07F?tvey#uDHN(nsKb>)y zZQ75;GYYR;1nUZT!2*(&a@HZ`2e`u;&VO|{L${l z*2ZgrO!+20#+=c=DS|6i1XnD@6`Si5-drAF>(kc$hb6|(LVsuL98#*J*~Va`!l5mL zC%-HP&QpL9#s{ny>&%}9E+BfLxVN>qw3lDq78%nCMoK5q)eSWKrC|OjP$1d^X7R7$ zPw{_$Ahp+B%J^X)=w$Oc8XpSGysBnXyV&@ z^NnjGbNdTgE0@~E#h>$~!e*`xGLiQdqrr%BAJVr>GIpUYv?j_ob`<_CP(FV28(HGq z{+g?wf|n-3QnRD*qmlOBxuftWUs}cZh|Pb}WyOKmz$em0s)MGtn6VboIXp%z?fPP^ z6?=Y6q60GG6Mfp8L*k4Gl=f5W)YoRIAWg6C7Pu?WIbnsUp*)T8-99xK`03Pd5RG?i z8{My@`+94M24^rN%cLN^#q+f-mdW(uKlrt-Kf!P8`h1njYBka|dmz*~NG2Rjfea-s zeDuyo?{Y<=%zu681~mJ>=z9KDpyBJ*r(XHWQF-WV@hMsg`x#yBKM%a}l?~56h?M-Z zHUzPn<0mkNSH8Nl^2M)oPZ_?}JcYNBFH~*Vy)fADbz$u5-Ek^rhA{mgxM8<{s%Jvi zm#dk))Pmo@R(+Fbb#mPwaCKjir>tLVVqf_x2POO^Qa<0&_%;6&bE_NAH9?hdPT7rf zBz8BYT;yx7!&qw zD$K_`bf}Hu7V%;r=|Z^)GM)XNn;XP(!HvJu0XnkjSCiku3gG$P(C}O)WYxx&3~sVJ*^J zk7#n?kQv@R`7B}&pyOh%V}Z{5oIMHg3F&K@sU%nN>r?4zAd15c8oEieHw}lvR1=z} zg&rEQQPng?v_19dVeA;BPw88I=e&v;P1Mp>1zXDC5I_FX*{cB^X7Is2EBN5OXxFH- z6q4E@KI|j8?Pq^;L-TtEsXy@d%j&X8sfJ06KVx!wd$S#@TgzQyj`+uJm3APsx4);N zu|nup@s@%*d(UG2WK%FBKKV?ksOcm|TIPSDhTgNEVAkIO{gSq#2|MK8@8Anw!@6)h zKxw+qXB10B8Rcj|qfekrXF<>6uOk|l6+L}!q(4?&v!kL1)~EaW49k~PY_(%wNyT=h zP?rWx_QYk4iI^6oZc+*ju&l|WP&0Ry`Vb!I>x6|Y9Gc%p44(z`Vh3zzd^%(ScoQnzD9@i1$WKF46 ze5YkCcGyNvc*}3ztLex4Al_f^fJM~wb>MyI9Dhq9nL4j9+vVbArjN!&fVMgiV+Q>$ z$)#&9hny7j_Xm7{`w;K~>>h#e?x2C2Z=XL?XkLweGjEd#OAX;r2fo#GFt@4|CYGOc z&Ck>mgV_b!Z6y9rdoRUM-dff|`!#PM4{cNVX`C6gs}cFgQR;u7ZPIxYup5BM8|Pah z#Ur*hSYp?r6f! zGr|htFe5bJj87fTaEqONANFjSJoKNrqk#VB@z`ytcBZY(YuYQBn^*%c@9vvw-iw~Y ze}g`sKzmqcyX!1=q76bnrO&7@{DAY<4P=5E=bpZ^aa%;%B!%#^0K{;uQ$%fuv}_q z_F$h8VnW`UPlV&RJPU{r`ssJqsT=o?E+oR_MTi-}^)jw;4-laR=~uX(LjKwBefQ60 z{Gaj`e9NMZDvT?URU5f_>J#DW7I&8RK3NqGT^Lr4Z@t=AO<{VV{}Q>US{l!1k*nWS zpSuK|HFk7DGU1KO;NJ=l)2~_XT!1$&DY_o{@4^4#A~}#g0do1RutqDqQN2~YFC4lw zoI9!4kMkNQ(6Zl;l>L4+S5HrL;hiqA3y=4l=+~5@z_agI~sXT zc=%>8F4n#FiS3ZvGif|0;B8zT#>B?e|D+^ZUea2eBsVds>2Ai5zQG?|Vzp z!$P!o*c8Aj7nqOP8yjR|Ik_kNSImE2#(HYC$@8lDX@3h$MJpeOU}IJF7@QeolUGz* zQc$;Ui=AARs$uKhK&~#Wrfbdu@eO;j|3iF%vs8ey1=X2Nrbv8NhLq}>fQY{d1#jBN z_$j^wt}sAxjUBUz;gDq*w6cR_wO+lu8tG1E7lWC`O#OSHLm@h9P4dF_%gKkskOnPV z?KYW5>)HbphvrCK=4vuwzi97_&a=Z_ z*yLB;0x0zNZk(0$?UxOadTrd+i?s9?BJeK&!tgD`D-j4cw;=+t4iM{n>OUm|8_8jn z$QxB#RiNAFhq6UVzqJ$^erqWLy$sOHdsK{O6P% z4HRNlS8OcKu96#uqwtNx^Jm@NyZLQUbyD5M=)4^_BzvApALXZ%uHMHQqm+Kj&{9K0 z#w>-OznRXpG%n4e^-ssnMozB9xj&q|W%yb91z$TP+{C=^<_Jz+FmrXk`Z6k^l9s=L zXYK}Vjht6WAX{Rsa>malSps%Sa`Nu}QN;!qC%@T`vxhu-DqT#Cy~knHOF1r9c0qbk zb!52=61BPxhcb@jH$RU(4_|;j-$A*ZNY{d1VMCp5fS<-hWtTj2glE&|N#1y@AH))W zcC?e0$;!8*L@u%>Q(uSHX>jSK;ZRQ>V}eY@7y#kwW3s-6ma9R;CM|>3LF;3kRNkRw zY-*y<$2+UM(O%RxaPpn~X~k;vrwC^iz3iyzNYPN`8=f)>>B;HdY zTF~Q)ezqQ#anam+7=Cpt$JPypjt(t{Jvs~4@`w7Zq5wI+3cY@-;J~th4L9Nj~hhUR4KM zbm?^l=|q2jXgrl6#0;D=F&sM8AN7prJ2`n^_-Y_Fvg*%X%jBwjY_8y2>VcnwzZ@u* z+}Mk;aNzTR6DN-7F{&rwnW86c>G`t(D*3pFs0|6g^v|w6|jwTg(=*vWT-IPXk{c;ljCi;@(Q^c73s9`Hn*PQL;ildcSBn zJ&8_d(-%@LXx8(**w8o8S}RU!q$eWa4B=b%+uK{nguTzFA+9*aSN{B@#y!iaPYCh+ z?q!>zx(_5CixsD(Cp-r)CeF2?=O;Xic#`N>DwvA> zeGd)n!QRheaochO;@7C<^f`QcVQqO6x#a}T>*2^J0Wy*9%-^8?2LCbSeVQl75XBlQ zt&!Z3bMqdk;Dfo^B2eA!IEgHygGLf#g{Xho&Y!%nw!<^33E!ypRx*f&sjt{kc>V?R zuM!*68h7CYn!S~2%hNp6+MWQ*6D?!W0Jv~O>oouB{0k|KiH*2uz=7N;e+qpsIi^g+ zrw`}gm5q^Ys$zO_)N^hcg9DsVuPMdZo=PekQcP^C*jo7c3#MOb(SjH4H~aTQ+W)Ul zSs%sM=D_*2d*F>p$IdRcft3$Mut+813u_7DE1x_-(+$1r4gjO7CnFgADnP&d4k!PK zr)8=~D2`PXkr?3`>A?zhP#-xLYYWapGQaPK;P9z-W{yu&MuOy!2gv%eFX!ZXGbB0zP;)q zZ7Y8P|6}>iK*&29u>m#>36`mTs_@R|aSq5HM6&3)JnWC!>vF>LZ>Sg!?dhWw$$o0U zyjatJz<$Y3cZE~UuSOazju9!nj2CQZOGdwD{JkAyQYm~&HkO#@D*PfcX_{Y`$HM{# zS=q&R*KkGR>cu!!qrd$5LwyrL`wXOUN&$PGPXrB3@E3`c{#f}Z{gi$t^i%pO5~CD0 zzGXFLD#ML)u<|Ya7uME!X32V0bf3v@!=rFM5pOvTuN0!@HLDk^Iv>si$_9QyCo69N=fCd9 zX-F|;DC13>Rhin+y_Q1+%a()m$>qMw0gT*_oV%v!Rttw`sc-DLnikPh|5ZXD)auIGiPoLBaU|j#JPZifQ*2Onl%h?MA6mMEmPYD(K?99 zcq!?!e}}{k)5_A__0mPf%CcGpWmhu8&8_XSy*s1!E{e9K+fIu44&Kgz0p|bxodN6J zb^o9Ld_HHMbIx-;&-HizohAy_>F!GbLn`KZFbOh}{jl#7ykf8f1DNAxuW+zDMR+FY z(C=RU*>z7WQFB3i@#hG()}NMVKzWAKPEdRa!cixhT8KXMJxaczl+5`Jmj4Mjg-H1a zk>b`_Zy|T`&9*4@@+}832DFmZzJpjFDZ*~-Z}f$g9eZ(hko*Sq6>B%^$;Kx2XmW=p zaYPHg{@H)mcfLq{q?vc9bc?cMR7bQO6KAuGzsYQC`dP|f+(DG2;IomnQw=^7)kz~S z%eByEZclCH6ff~p6IiXAP7&ChI})*5rAB;8Pib#_94qaOe-H7{ z_wQYW*n7*aH~#+S^XvPa{r%17)*rw2q36w;&#lpJ*PK5?s6%K_G?QO!-7(G7KD_@qA3?^id!B8@xK{o9xLRMh_~tuM491$K8ks~;E_q}6eUa`tU0?Hy14T~Pf_zjzH|1Dh$(B90a}SKWLHX~XFE}1r20H)6=WV~D^JVpuQt2G3ijpGSdBi%^B_cJv6^B_*uq9P=+tUPM@u$O)M=b$DVW+9Pl)kt*jiD z587Ny0ulPpo!eZ6IeNmqsWBFF!P;F~Y4g&Vzs$`A-wD@Nrrn-79C+}NmPdH?%n}DJ z?~9m?G_$ziH?RgnGn@;aQSQ=lcN($=iJ%J7tmA@THPM{XDEoRWBm=l$Y1jscOAD)_ zHa9)5f}S>d!a}Re;wBg%O4=K=k31NvHhKDv@m<9%_sxN+?P1K#U!LEAc6Eo2Hy zw!B~8w?CNtKh6;~pb|!~3ig$&utiGJb75)TM@nn(j-`C>tHr4AT^?V*ul)1Ha{*7) zDrXZ}EZgO*t!C%ms^-T3S3oA~$9bPT&qmi_W~%|$9T9HBbo6cL36_%S8}-73`uCk? zz=SwKg++MFS)Z4A)~}uC=o?=Qzwh)2-}x>+&rN()=1uYSOUj$-{qxi6x$ze_(yEET ziKhcJKcPA5-B1<6bhCrRte6ZQbo9S*ELENNk*nV^C271)j;dof;K z1l5al7XZ&z16HTrBufX|pta7@j7`{?S>zr4)BB$@K4m*-iX5eE;6<_~qCggc%lnBZ z1^Zl82of@`l*VkxhowV8jKDaW#G*JnRS=@tUGSi!c}Ki!5)Hp;p&mA4K{s= zUHH<&*`ilvi}C1T#MpnRCt3{IH6Tq+8E}6zyM|Romb(^s@Ac{-L)|UKg-8~gW+LH8 zvD0XsP`lN_Hdq(%$n#BMX>w2NN?u$<-&GL_T?lD?ED~d<(XMM0Hj<^9JM1pN!Y~rU zVY?T09K+0ZtG>MYU^U4`+r&kXa|GUil@_U)PNHhDA9&-_eKdX_gtMTDTif~V%2e1l zO;IGqA%p(#-U^FXL|^Vid9{y>!r5cj5nuYhGzxNm?eB`|0FRA!x z?$Sr@+)j1-7X4{?i+f#TWWTVWj=nlaKf-LK)wR_$mmC=JySnm3mKyMpC58LLG**#u z`UbGAJe$72BUqLdiw?^xE^6n+o;{DSlqY<5gGPJ;67*@}cDc@!DDt*ESjwoI*7~p= zSj0eeDqx7P^mMqSwc5p5srK#iVWd;_rZc0I%f4zz{zc-BC~DZV#leVw+%IN?57pFX1azQR+ktA2I+pR~Zm3@!_O$yTJy zJ)|ueI%5r_B+*NoBiIAM@`OF0hd4XF{?!n^*!)oE=IdM*W~Z633;l$j6}G@e>f*8l z%=Z*w&oq{#>@6>1)~R0(OkK|O$!kG7eT?bJQo;~H59y*Zf!SE_VwX)EgZp^spzfGP z+!umDujfT(VT`aDmLM4DnZ0XS`dtqjdkglC^ZX3{3SQw`R}K(3P_s^jHHq0R7gnk) z-0tn@Bl@P#@h-K+S}{(bcUc1UNE6gX%$vW<1)f)2G;{ta8$C3yY5iyfcO%&( zF;3vJKXQ`2kRSYn;lYLl)Q9~6GY@}5ID+lFZB0`zS(d;1FmDt*x97!Y(B=hrmL zm2t_Sah&KzD*s! z)d`Oe@g06u%|LUUr_Kook53g2G}(o;Ro{Cm#Yjt8O4M0qE3eYF>f2x8Qc%V!$Oi@> zbr!5j6}MJ`f*gXpU#cVcg6G?MnqT*ZuLeAL{*?!E3-Ww(oSQTMHNd6*(vK%Qm-Ym( z$vyTRP8Fm>b~so2S-Kn80_f4*h&R!l9Vg!J168R@l^iV1^}ll5haB@U7ZThj10O;P z>R$icO7moX%q(!ffpe%brtVFh)|(?A;V;ZOa~kNhN8}~uU7j8CQuD4=&ju{1$O{~h zU-EJ09}sWsjn^ZjoV$H0^S2m5Gb0T37i?(&9E~bR#dPsR&6ghP-&ojlA{bxUvG0J3 zvi7Gz8|aiSVi$N2CC-B-n?(p`V{L6WoR+uG$!H{Ol`u|>$g|7Ev`r>)*rwP5oM7f~ z9L~J#ruyCW+rVwbTCiGP_)UFO{bpyZ-wG*|4(^yy6*nj-X32@3{1r=bfw$aPp=V&CT3 zj`7>JDhS_LEO-`A3lMV&s|x28G#cW3Qbcq5^J1+J*niTF^EZ>Nj;u?}Zv*Dd?h7^Q)dgfI?yYrsNc$&~4b47nat|M#Bz_}&OE;Hr(<%TqQ9Kh zb5)^i{4{2I2&v~>fc1a`NZeM7`ZDzR9bj>9hrvFmePw^6Z*wDGg|*9dOR3<0h9%b1 zXU~()13KsLv%>=#ASUqCx`PU>P}v>G&MT~OvtGS7IyFh}%_qA(M`W$tm6qG&vaxLh zV^kdao2;$_hl!yzn{di*T>X1WzY*z~<*;l${zCn}E&V&UbPcTEUa0c1-G`iU%_YDI zBlJ2o=ye3c6Rk6{Bdn20Zi(z~f7_T}F@$ymUAOZZe(gob{lrb$uzD+?!=Jc?K~L1l5qGyz2WZ zkmo&K?%cAW7hmOk&`N9~__&|Y+sAi+1POk)1^N{y`PUYhzmiQJ?Y6Hj>EHh9lHs{7 zqVNd0fTW@|T5k^EtO)lc|Juwn!uMX$EEGDR;n}a33(>0K+Jbe5sWjq;Jhy4P4q}J0CkWb3zpO+xw_vEEG{rZqi+^) zhXbI+B)!G-ci|e0%igfDZlf4I!({ojd_UlD5qq<}ON89RLEwZ+9!S%7N^f_i;AwI< zd1s(}1cj?p(y;TgU_uI?G>Q$GMfgd42ZK!AaN+7=F5B-`W$kbdb<5{i%IwPyz8Mxs zcO>w(HB+tlV_ca%-<-t7L&?LMZNbv{7+63whLwBFfGwDp&$>l)RE>oHuc z$UW_4gj|ZLVW3ZyGSVj=)!8&j(e9bEIg*!p<2oanKwDOs~`&4o3VwWVtVupYAavC)q&d3^M`l64ix zX+GY+pjx)Dz`BaEYT4$Q9W>}439i>w%gOd?d6cJGwz?gotL4$H)pC-%T267TM6NOR z801PrThfst)m1HLAoW;WnYir7tL1U*D$2`7iY&zDAm@0*OfXf;6A_!s4wSiot5(aC za7{K>%TtizE~J=hx*O+bu!=0s=|P9%f^R{BgCzSy(hH3&=xmf5Ho(sW!PT~tU$StT zwRsbB0B3%^LnnydH!3~Q+Z@?7O-^R+Ms8|t<*QE3*<8#tO&4rWGDGYAh#@T}_!=AE z;0&C4#Pz0|nF+rf1`jSo^Xrms93w1uVknV?;weZdaXF?e zefoJnBp3|T8kRJ#@Y=cPb`?kMn1yy6ZJ}~zU;aWp5919jZVx@veWV7ui_}1O=UuhX z4FYE#boXe~wV+!o1idU{WXp!ihPD&^k`5)hW=wNxANGI9Up$A#BTBwyL&34d^$-#XQ<$DB?G9@b&_pc@|N4Zow1N^${ceYdM~U! zmgnw*rc~y@M(EhNuLUy4bo!ttlXe4KQ@)7ojP~in694#n(9xNVu)m?gAeXALrjCs% z^gS;p*x|#0=MH>ziO>EDp7U66Cgj$}pXFXZe~F);i$0nl^OYVUS2zWUxx?WiI=R%^ z9eQtUYVKN>5B#5R|aKEBg9o^j?w!@&lqeUJ)H|) zlFPvt%JZeUl8aNs1d*@IOq=Rwqb3S78?8bGVA?Syu#d0)$Jb$;LRK}%paEi80IUFdM|Dw8wq^cU|+2`3MXN7s}=Do-}XYysS9UV5|wEc zP6bNE(L#a%YcaxCxR~t=d_gq-7y1tV^8oev5u7*F@9+zUcK;u54(JX`MWc5QFg22! zoCd!WXj?YgmQA#{9C*E>v}z$5w1>OB6UxToO7zwNp6PcMn!Xv}oo5()$;3N{ZN??y zpaPaAx0JeEBJqarXIJ1c&M5G2b1#$B5J~iLyDS2~gXj+AH;(4|)!TEO3;n3Qcw*Ba ze06^xU-p#u3uwLX5?6Z%z^h9?Ukm8CgF#!Y2pXAt8jV9mP=mY3GvS>Yp{DL-XpgYe zMZSSSZGXUQTJ8Y%(%>f3Zg5YY(EcX239__XG22{UT~a*^?|2V0#lzh27S-$bVr~(= zL!H>K1#;CD=#e*Rv`jwDPFkrSfRm>d27rE$D;&g{dAC!$L&WSebr@Phy<=taPbo_f za~icf_B0YrN12t+re4+q8Z_^KhZ;{K(0se6XLk1WG{L(j2M^s%(_vn$7F!^_x!7wfEB5Xdr+A@3RvfGJ zEZtEb>%q17aZK~DU;H?x-`rtLhuy9TqkUK{?$_zR-XJdW#-oOo|7Q){%MW<@w_$1E zf7Nkbse|TQr?OLCzWq%XI{LoJbj*7*Z@s?ZgsAa90E@L48$}j_I4U%wKLI`3D1hpd zdY{iSX8xHIy`vWG=gSO`uUn*W{R(hqSh2URaXDMxM%uf57HjM{S3;Kr*;Sj(eNc>p zyljh-m#ju+lPK!f>OVRPLkKn!e5 zk>3YOUIF<8oYPmX*}oTBTxn&y%hRySZd99vXxd#j+$BV`f<_CCh3a#pmDS#|*7ZMu zv@-4;ilP2fCk9%$iB|)AogXy4Ck_@MYcU7jbh`R^_ZIdCB}wo83~z>b4{qYJ529bd z8w}8V|Ll;iJsr{jEcgca z-z3u=lCJiA6ZjjndHF*Lt~s!^7n_H(9^=*}jqil#J)XQiKI|$ju`Ssz7i|60C9TZ} z9AB_gt%H3m8MQikX}-_?Sst8sE-*7m9n!9~=lmVtrq}$AzEJaSpb!=e3AQ0jaRmHa zVm}V469=~N?{GV5_shag64gSos%JNmr3oi27M!@GUUn8E)e5MTARF?11W9=0(ToDl)1XY?GELd=an-UK_z1phad3poh*ikxJ z)HnrvUY5k!xUJj)?e++4p(?;`59@7~u02j&3-(QCDeM5ugJ$rbaPkox5yDADJGSYV zde=7BHD#A+4vXHp4x=N-`|&1c(4_jfifk%EHXG8nW}y?k$}#eYq{hs0VBU0w_uyZ` z>Z2BgB-KZh_7V6;RP{=Wixwut96}K9JKCwz_u>p|CRhIEcs@D>I*gungxs0GgYI;i2P`q7~g1fmAZn*28#9G zZL;b3fTy<<%4hBsab6yWKP1bfM$SCXHFRB?Yvj5(p%hvt(XM%}#C39D9=xNx zk?%^!S4G~DFB6+LR;=sv1RYVZz5&i4)z5*$*q4T6Gs%CW+uI>+>fGaP+f2MTRhrKC zj<^AK8hFr5jZD{?BIK9bTpP+uVXd2)YhAh67dh;UR9cc7i|HPdc|SI2`|t?@_duLwTJa*y#f#4+YQ zk(S1sGvaG-9<8+266=tPU>^|_(xn|zzh3{2%zPn`1WO6j%JZN#G@~B~vLYCU zd~AiJ`H^-(Plx!9WUpA3>dAB89Vkv|HF4^w(`oSA74vn3t0znE!V4L=_378ob9d2t zeL0*|e>sruxf%dpDiQEW%gEGW&9YR3lTi)2dl__v*qrAfnGWAKW^P-Dl!o1b;%Ofy zTi*ApJE*q6J71qIA=``XMflX?hn5k z)P@%nza!DuA71TA!W*^4wgs3_H7skvVezF9XZap{o#8T%XT(ggRg*1Gnjs9=ajbcIQ#+kfvhy|Dk@5SGC>&0ox$EUZbt{OxA& z9bnCyD08y3@fgJ_r5}s6y5;kN6thWQcP*}<&9~(2#$5O}t2g#^>F&gV6FEnyG zm$T9pBYuMOI}zAtNP46@z11#c!<+0*ac(U4^>A@q<38u$bHl~d#{F@FreA@!P_z&X z)QGBr$X(0~^8Z}aX=iaerc&>1Q*%3AKlnA%39hhrzUzv}U@6{g zsvL@6rhbrf&WB$omds7w<+6!`06jvt???^QoKIpi-oS^;EJ~eC@-W& z^ZP5`JH_V|M?%YHVxMR4f3frYcX=u1!>xK~etNKzb(2pNnjg8csXe;CTG0B5E=tfg z!L-2*&qDT)THM)z9I(+hNq|PTYOC|PrsHwU>?mOHwN5!mqHzc$8d+2L^IcO&zDu=U zJI3I5Tnk(GfV#fc>H!ChSyc~rNb?oHPm|#H`1&**WEx%;l)dH-JT5KxvK`Xp4!eUm zS=`n=UhaS_E$=28xD5ZWBj6b;&9wm@)3i^>lD(UFU6ApjmOl#_w53F`$@ZNE?E|Ym zD)DD$hCyHF_-n%xibl*J8gyPedw4nT^b`_!itWI!M zOw2YiwRY)%=3I=$z-|wCEQ?(%;}hS-Ml6n3D0Q1-if zu;$noyQa|E8@`#r=Q#^n6lfauof`De7impmR^9Z{lK$p>C9;&+p|kZj+e+x%lcYC4 z3eVNC@mnIke+y&Hm3r^HPUg=&#^rQK--d4m`sCU{GdV&wu}Buc186Hour!jl2zho$ z+I)0iV@OI5#kQ*2hw-qB5xuaGU90!(ZP#l;(qB5koqy%aLSwV~%Kc0y{jcjh?0nhxcDr6R4zo#;ihDLgevC!G z3r*dqHeOW@30%+_T;){1oyYwks^9*{K)xdR8kg^MoefY)b2}|cKb?jD4VH4x4e@v5 z1S(gOEIs28lMkCW4+esVjbb!tiv5O{iJ$9+pN@Ut>r1L(DFuzNR`rAUm1~5!GdAIY z_u`TZUY#=o_LB<4-3y?_r%uQ(aM^|6haqXy2V|=p)=f_BjNKpiijrzK>@RbCx$9~m z_+dn+a8jqETz`!0EAfp*ie)8Up~emr2P$@&IDbg$_<$@q#k$C65Kf8JTYJxpXqT#Z zK|c9yb5Dz$6Zx`p4c*gX4)YCsFBVO9j8uxfBf^=DhYj$#w5e{Dmm|D9Xzhr8$FNfcn?NCH zX?K*8j%>zJTzW?knA;0=gRyUD1@!?Qc7v=PR?JxSfsiz-TL&8oCcxq$={n9z7fR%I z>5)%{rKMCsk2F)db6hdN>Pc&&GXVWx=-{#=6G34CHuLhsT|1i{btWVgcUoUmt2r)~m&M0zga4~RuvV2I z7|y4aS%ugFNviB>6UUS>i>;u|<)2Sj5_}g!rcY-g-5=mp;XXgF+G1`p@6r}KOY&Ws z;tjw}j$h)(MY{<;sd|a&@5Mzni%vi{^#oP|4|_+vl8&BO(;s`|4XK86nJJ0qGsjgq z<6HK?o(^YLc?Tg)QtF^{^cj(<@*8R$<+#>= z-mA`ZMM_%Nx(HO_i@q$-Ye?ev8=t}}5GQ!E;7KkYmOz2$xo!k(xa$Z2wz}ady@}9< zuszU6Wjx~>2U?{v-|;P3N2Z|6zxt@;zxcR!9M_EZMx;G`EysX6XM2bitY@DGVh*os z(7ngK{c~Ae&VJn^{Q`KnwgvtSuuqU=X&=@wN$#Vl5k%!ysDu#s~*v zdna)mBxxpm4L-J!U21^mqi$-77mVbEl)AA!%h2s5J3!mz``sb&HUNyxHySmjtYg_S2$mkcGsst>U zM>KE!t7_o|>^QUh&pEdXWoPO;pSd>I%XO-*f81{7%&-Dz>{NB-!Mo;m$Lz}qMHb^n zA^FzG&MlHYH1s0g=W9c{_MJ|{nS?f;*S3f4p5Vx;oleKKgeukDr3H)P_SYW@$w7U{ zlwEL{FJK{^^p=uZt!BWcJwZd&TS%>|T3VpWbzIgu{t?ecjqsj!C_IJyae(E5&u(@` zonaZU66Rr}Kv#!kWaRy!&JDNN*ctxKPSvSrpsC#9sg5f_J2>-e0?TOiA??r32ULyW zZ|J+&7)S7B&)zm8hcB6iZ|LDhnT;UaT-SvL4RBoM@?t{J6m{zHEgVM{m{ccgQ0kYS zd?5npSGKIhaA>U zUDr%_12uQ*Zg8F2>k0WC)RWU0?!BQ7ShuB?M1^9N7U)AUXo0Fzdo5aNg}yyJ*%Pes z)S!quQ@YNduhS$_)Qpl>6R`uG#fJ|PaBH4 zzPYz|F;jAfp4{vld`5M5Nx|oF!eu7p2F8L4tbygmi~j_V>z~DiZ=Y;zQ|Xts8DqHI z+JFGNu4Z97AW(n6Cp;BUO(`kJ3fP6H0L>j|faW<#<(nF!%uzFC>D4Z*^U_Q+Y$4{z z(r>!Pnq_Gls37$GC%HKX)Rrc)^9y-(Gi*6_Xkq>NNq395AfE+mJ6P~kM?_<@5q5R! zK-(o8#*g=nu$;kyui-xu|2%Bg_J;=mmZZ=-5z_r!UFd5D*%XuVWDOpeYrSE@GiV6# zkdz*Id&8r=LCet&#=@Mw0d01HTiH1~$hjir+drV1KY~mS#SHyPjOhaw{I3syOW9ys zyB{D;TWl*1HpGECXf6KudbD<+ab(Q`@gwJmC)0edZ~6%ID9&t5)`VF0 z0&&EXdDnP;7xWOE*EocU25)H7FGVCPyzZDA-{!e3i(lgEk zH+N=7!h>!{ToBZ-uLBPxUkWTp4g~H?{tl-%>>#fA4s?kB!FfP!I*xI{teeAbzG(8v zkdvV{r>GzqqxRt&EUF?|+HjOvxT4NLW|W$Z#l@un>P8A4DJXu;QSM*j^$ips?b9EN zLi|Hr9^hhstk)LNc*xSCqZ+)O-}_coME2PG$|jqx8?NhXOw)P*m9|=GG~BR6UNe;? zjhmH!!wtLeHB%F;nZ*gK7q8y6`rK++njXqPc|s^1|M?-#d?vc$>cLmh?t0po2t#E|{31ZKk=*Miu72 z>&$IR7osrtL&)K3`~|kL_q(Zc3|2uBjf34EXL zyF=1%x@G9h*W_@cV9x++hAp7=(D%){I$hl!PNm%m`YJ|TVi3plH9;3E3%f_$2x z=HPnAf)ZMz&B&`t)D&xqj7@qAq=$lP)o_>Ea!b1J7{!@dSu07la7DMISy-d=%&eS6 z4g1))q=IfL4VoDxBx68vs@}8{Z>NP+I`U@rKC4qAkinp4`sz=+_>3sf9~d(>B|(pp zS>{1{Xn4M+csP3D51>)xDwt9zkU+L9@vYD!7ce6L3x=gLpv_Cr&SSv~9l(l#odSE; zb)7zof6dqYjD;>$drelpxX|UEX5$_yR0)QnD)A*J-^|_g40y?DXx1sun%?IffJP!~ zjWwOax1(7}=EMC2hd2N-`zZzBpDwy3eeoeE_*Nt8Z-`4rRb?J=cN}ZWH|cx( zEt0C=NwTy9IqP<_imT-8;nY}IF?_}e>rH|l_4Whho#d8KlB<6@IIt z!;@85Dg$mY=O|=Q(0lZJZ`cOdobu7r3?yFDA6kaiJiFu~qe4wd|QkN#+>7zG__nrX)?h5@Tmp)V=!U=JYF zY-Sy-JnaVsk>0`M46x}Q>6MUTr|m^OGU1rz`VbFRDUl}pO z4DV2;hWX+v&Sc-|<+b=8&Xxl1D&#<~KcgPhc-PS(#l9tb;M*WyHk(HJZ#2TP;Fx&- zuH~TX`1tk|@Xy22U&C{7isO57!1Kl)g!9`5%U$66Yl^^4#w;gUsRQBmK!S@UT@6sX z5(cxR!839js0H_m8gZvH&gWmg8GS}AK<&(6K|7MT5YKOS^6e@fHk;;XeLC3MpgMmY zHhX`_SETK2us(`6l~~fOiOS9z#*#`_Kl=E@j7KvOJ|vc`Uixs!V=LBhb&uLPKwS6rL$xbnmmVH|*CNu35Iav|{Dt$>zejb7#+;Y|dM;dRfWR zC(L-cQfY^Q^(HaTUG_-XnzhTQ#pe8i{LH-kS!TqQm8>u?U0wG0veiE(?JZ0wDO<5@ zsd;UMxfG?YU1nY@F8jBv%N{Q)T{hXAy!6NH^ByZLUAAV;!;h_4@q~GGZ?#m=9kTb< zjCs3&sd4FX8F86#_5Bi53o@53dpvXP+9&2!vM^pNJ) z>2IbmeSd`0aRu=1=LjFf_3Pg2>kOtZ9E&`-ZsK|#*G^ni_C~~=u`_)Op1;PmF`Mas zhvx^!qnt;VJ&LLIabFvp|^F^&BKB&N#h zkSGcvO$eF;EuqW-CipvXqq=>{N`6Vt;X5e#9PQmy@xriGTX=Q-qH1Ua`N7knP(Z_aKGe zKVCGNLi0m=uH_+Q%f33Mgw=n0RtbFr=P4oDqJ(Vu_YO+OY7Rw0$NEUfruT+}9lLhY zukoIz2ERY;+b65<$;eM=yD%Z{p2=J67hZUx@a_*cHUGB$z#fQ%H7As?`ftC@i+pEZ{;-vrhK3{C zgqt1rT;gZv&dM5L?jxCvwJk1QEK-acX3gr(V& zlsS;jZqI6aHpFz4w$p^Cx|jK5pFjEPHQPVK2b<+1b4L zv$C`9iTolDMH3h0JU#xwO3Ka%A5h^R3!!e*0#{u0@T$6b^rhX literal 0 HcmV?d00001 diff --git a/boards/holybro/kakuteh7-wing/firmware.prototype b/boards/holybro/kakuteh7-wing/firmware.prototype new file mode 100644 index 0000000000..5c3a914540 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1105, + "magic": "PX4FWv1", + "description": "Firmware for the Holybro KakuteH7-Wing board", + "image": "", + "build_time": 0, + "summary": "KAKUTEH7-WING", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1835008, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/holybro/kakuteh7-wing/init/rc.board_defaults b/boards/holybro/kakuteh7-wing/init/rc.board_defaults new file mode 100644 index 0000000000..8bad0d3cd7 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/init/rc.board_defaults @@ -0,0 +1,13 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + + +param set-default BAT1_V_DIV 18.1 +param set-default BAT2_V_DIV 18.1 + +param set-default BAT1_A_PER_V 36.367515152 +param set-default BAT2_A_PER_V 36.367515152 + +param set-default OSD_ATXXXX_CFG 1 diff --git a/boards/holybro/kakuteh7-wing/init/rc.board_sensors b/boards/holybro/kakuteh7-wing/init/rc.board_sensors new file mode 100644 index 0000000000..c5c3c9a59f --- /dev/null +++ b/boards/holybro/kakuteh7-wing/init/rc.board_sensors @@ -0,0 +1,20 @@ +#!/bin/sh +# +# PX4 FMUv6C specific board sensors init +#------------------------------------------------------------------------------ +board_adc start + +# Internal SPI bus ICM42688p +icm42688p -R 2 -s start + +# Internal baro +if ! bmp280 -I -b 4 -q start +then + spa06 -I -b 4 start +fi + +# MAX7456 OSD +if ! param compare OSD_ATXXXX_CFG 0 +then + atxxxx start -s +fi diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/Kconfig b/boards/holybro/kakuteh7-wing/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/holybro/kakuteh7-wing/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/bootloader/defconfig b/boards/holybro/kakuteh7-wing/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..3563334664 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/nuttx-config/bootloader/defconfig @@ -0,0 +1,91 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/holybro/kakuteh7-wing/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0050 +CONFIG_CDCACM_PRODUCTSTR="PX4 BL KakuteH7-Wing" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3162 +CONFIG_CDCACM_VENDORSTR="Holybro" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_USART1=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/include/board.h b/boards/holybro/kakuteh7-wing/nuttx-config/include/board.h new file mode 100644 index 0000000000..36882deef1 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/nuttx-config/include/board.h @@ -0,0 +1,503 @@ +/************************************************************************************ + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#pragma once + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The px4_fmu-v6C board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The PX4 FMUV6C board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6c board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_1 /* PE9 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ + +/* SPI + * + * SPI1, SPI 3 for sensors + * SPI2 for OSD + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2 /* PC12 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + + +/* + * I2C + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11*/ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_1 /* PD12 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_1 /* PD13 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN12) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN13) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PC1 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PB3 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_2 /* PC1 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_2 /* PB3 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8) /* PA8 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13) /* PE13 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15) /* PD15 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0) /* PA0 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2) /* PA1 AUX8 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/include/board_dma_map.h b/boards/holybro/kakuteh7-wing/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..3bf265085c --- /dev/null +++ b/boards/holybro/kakuteh7-wing/nuttx-config/include/board_dma_map.h @@ -0,0 +1,81 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 */ + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* 3 DMA1:39 FRAM */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* 4 DMA1:40 FRAM */ + +// TODO +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */ +//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +//#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +//#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// TODO +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +// TODO +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 1 DMA2:45 */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 2 DMA2:46 */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 3 DMA2:65 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 4 DMA2:66 */ + +//#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* 5 DMA2:71 */ +//#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* 6 DMA2:72 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 */ diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/nsh/defconfig b/boards/holybro/kakuteh7-wing/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..fef5afff6d --- /dev/null +++ b/boards/holybro/kakuteh7-wing/nuttx-config/nsh/defconfig @@ -0,0 +1,270 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/holybro/kakuteh7-wing/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0051 +CONFIG_CDCACM_PRODUCTSTR="PX4 KakuteH7-Wing" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3162 +CONFIG_CDCACM_VENDORSTR="Holybro" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_IOB=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_TIM15=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM2=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_TIM17=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART5_TXBUFSIZE=3000 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_UART8_SERIAL_CONSOLE=y +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y +CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/scripts/bootloader_script.ld b/boards/holybro/kakuteh7-wing/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..fc0a5589be --- /dev/null +++ b/boards/holybro/kakuteh7-wing/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The KakuteH7 uses an STM32H743VI has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743VI, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The KakuteH7 has a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * depressed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743VI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld b/boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..ae07f4bfca --- /dev/null +++ b/boards/holybro/kakuteh7-wing/nuttx-config/scripts/script.ld @@ -0,0 +1,228 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The KakuteH7 uses an STM32H743VI has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743VI, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The KakuteH7 has a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * depressed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743VI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */ + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/holybro/kakuteh7-wing/src/CMakeLists.txt b/boards/holybro/kakuteh7-wing/src/CMakeLists.txt new file mode 100644 index 0000000000..7ce77afe67 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/CMakeLists.txt @@ -0,0 +1,74 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/holybro/kakuteh7-wing/src/board_config.h b/boards/holybro/kakuteh7-wing/src/board_config.h new file mode 100644 index 0000000000..3e70a227f4 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/board_config.h @@ -0,0 +1,270 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * PX4FMU-v6c internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* PX4FMU GPIOs ***********************************************************************************/ + + +/* LEDs are driven with push pull Anodes to 3.3V */ + +#define GPIO_nLED_RED /* PC14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14) +#define GPIO_nLED_BLUE /* PC15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_OVERLOAD_LED LED_RED +#define BOARD_ARMED_STATE_LED LED_BLUE + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PC4 */ GPIO_ADC12_INP4, \ + /* PC5 */ GPIO_ADC12_INP8, \ + /* PA2 */ GPIO_ADC12_INP14, \ + /* PA3 */ GPIO_ADC12_INP15, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PC0 */ GPIO_ADC123_INP10 \ + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY1_CURRENT_CHANNEL /* PC4 */ ADC1_CH(4) +#define ADC_BATTERY1_VOLTAGE_CHANNEL /* PC5 */ ADC1_CH(8) +#define ADC_BATTERY2_CURRENT_CHANNEL /* PA2 */ ADC1_CH(14) +#define ADC_BATTERY2_VOLTAGE_CHANNEL /* PA3 */ ADC1_CH(15) +#define ADC_SCALED_V5_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_RSSI_IN_CHANNEL /* PC0 */ ADC3_CH(10) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY1_CURRENT_CHANNEL) | \ + (1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY2_CURRENT_CHANNEL) | \ + (1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL )) + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +#define BOARD_NUMBER_BRICKS 2 + +// TODO: fix +#define GPIO_nVDD_BRICK1_VALID (1) /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID (0) /* Brick 2 Is Chosen */ + +/* + * PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 14 +#define BOARD_NUM_IO_TIMERS 6 + +/* + * UAVCAN + */ +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +#define GPIO_VDD_5V_PERIPH_nEN /* PE2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#define GPIO_VDD_5V_PERIPH_nOC /* PE3 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN3) +#define GPIO_VDD_5V_HIPOWER_nEN /* PC10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PC11 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTC|GPIO_PIN11) +#define GPIO_VDD_3V3_SENSORS_EN /* PB2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN2) + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 17 /* Timer 17 */ +#define TONE_ALARM_CHANNEL 1 /* PB9 GPIO_TIM4_CH4OUT_1 */ + +#define GPIO_BUZZER_1 /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM17_CH1OUT_1 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +/* PWM input driver */ +//#define PWMIN_TIMER 8 +//#define PWMIN_TIMER_CHANNEL /* TIM8CH2 */ 2 +//#define GPIO_PWM_IN /* PC7 */ GPIO_TIM8_CH2IN_1 + +#define HRT_PPM_CHANNEL /* TIM8CH2 */ 2 /* use capture/compare channel 2 */ +#define GPIO_PPM_IN /* PC7 */ GPIO_TIM8_CH2IN_1 + +#define RC_SERIAL_PORT "/dev/ttyS4" // USART6 +#define RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX GPIO_USART6_RX + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) + + +#define BOARD_ADC_SERVO_VALID (1) + +#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_VDD_3V3_SENSORS_EN, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_PPM_IN, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define FLASH_BASED_PARAMS + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/holybro/kakuteh7-wing/src/bootloader_main.c b/boards/holybro/kakuteh7-wing/src/bootloader_main.c new file mode 100644 index 0000000000..cec6abd467 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2019-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/holybro/kakuteh7-wing/src/can.c b/boards/holybro/kakuteh7-wing/src/can.c new file mode 100644 index 0000000000..a4d6682917 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/can.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +#include +#include + +#include +#include + + +#if !defined(CONFIG_CAN) +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + return 0x1; +} + +#else + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/boards/holybro/kakuteh7-wing/src/hw_config.h b/boards/holybro/kakuteh7-wing/src/hw_config.h new file mode 100644 index 0000000000..f41ab30606 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/hw_config.h @@ -0,0 +1,128 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1105 +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (16 * 128 * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_RED // RED +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/holybro/kakuteh7-wing/src/i2c.cpp b/boards/holybro/kakuteh7-wing/src/i2c.cpp new file mode 100644 index 0000000000..9ea96c9206 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/i2c.cpp @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +#include +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusInternal(4), +}; diff --git a/boards/holybro/kakuteh7-wing/src/init.c b/boards/holybro/kakuteh7-wing/src/init.c new file mode 100644 index 0000000000..0e3d27db7d --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/init.c @@ -0,0 +1,276 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * PX4FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +# if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +# endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + +# ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + } + +# endif /* CONFIG_MMCSD */ + +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {15, 128 * 1024, 0x081E0000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + led_on(LED_AMBER); + } + +#endif + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); +#endif + return OK; +} diff --git a/boards/holybro/kakuteh7-wing/src/led.c b/boards/holybro/kakuteh7-wing/src/led.c new file mode 100644 index 0000000000..5cdc0f14e8 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + 0, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/holybro/kakuteh7-wing/src/sdio.c b/boards/holybro/kakuteh7-wing/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/holybro/kakuteh7-wing/src/spi.cpp b/boards/holybro/kakuteh7-wing/src/spi.cpp new file mode 100644 index 0000000000..7cdaf3556c --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/spi.cpp @@ -0,0 +1,52 @@ +/**************************************************************************** + * + * Copyright (C) 2020, 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortC, GPIO::Pin8}), + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortC, GPIO::Pin9}) + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}), + }), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortE, GPIO::Pin12}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/holybro/kakuteh7-wing/src/timer_config.cpp b/boards/holybro/kakuteh7-wing/src/timer_config.cpp new file mode 100644 index 0000000000..eaa8d887e3 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/timer_config.cpp @@ -0,0 +1,64 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer15), + initIOTimer(Timer::Timer3), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}), + initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortB, GPIO::Pin5}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin15}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/holybro/kakuteh7-wing/src/usb.c b/boards/holybro/kakuteh7-wing/src/usb.c new file mode 100644 index 0000000000..70eebc6fe0 --- /dev/null +++ b/boards/holybro/kakuteh7-wing/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/docs/assets/flight_controller/kakuteh7-wing/holybro_kakuteh7-wing_bootloader.hex b/docs/assets/flight_controller/kakuteh7-wing/holybro_kakuteh7-wing_bootloader.hex new file mode 100644 index 0000000000..ecf8799a21 --- /dev/null +++ b/docs/assets/flight_controller/kakuteh7-wing/holybro_kakuteh7-wing_bootloader.hex @@ -0,0 +1,2712 @@ +:020000040800F2 +:100000003217002405030008A9020008A90200080D +:10001000A9020008A9020008A9020008A902000814 +:10002000A9020008A9020008A9020008A902000804 +:10003000A9020008A9020008A9020008A9020008F4 +:10004000A9020008A9020008A9020008A9020008E4 +:10005000A9020008A9020008A9020008A9020008D4 +:10006000A9020008A9020008A9020008A9020008C4 +:10007000A9020008A9020008A9020008A9020008B4 +:10008000A9020008A9020008A9020008A9020008A4 +:10009000A9020008A9020008A9020008A902000894 +:1000A000A9020008A9020008A9020008A902000884 +:1000B000A9020008A9020008A9020008A902000874 +:1000C000A9020008A9020008A9020008A902000864 +:1000D000A9020008A9020008A9020008A902000854 +:1000E000A9020008A9020008A9020008A902000844 +:1000F000A9020008A9020008A9020008A902000834 +:10010000A9020008A9020008A9020008A902000823 +:10011000A9020008A9020008A9020008A902000813 +:10012000A9020008A9020008A9020008A902000803 +:10013000A9020008A9020008A9020008A9020008F3 +:10014000A9020008A9020008A9020008A9020008E3 +:10015000A9020008A9020008A9020008A9020008D3 +:10016000A9020008A9020008A9020008A9020008C3 +:10017000A9020008A9020008A9020008A9020008B3 +:10018000A9020008A9020008A9020008A9020008A3 +:10019000A9020008A9020008A9020008A902000893 +:1001A000A9020008A9020008A9020008A902000883 +:1001B000A9020008A9020008A9020008A902000873 +:1001C000A9020008A9020008A9020008A902000863 +:1001D000A9020008A9020008A9020008A902000853 +:1001E000A9020008A9020008A9020008A902000843 +:1001F000A9020008A9020008A9020008A902000833 +:10020000A9020008A9020008A9020008A902000822 +:10021000A9020008A9020008A9020008A902000812 +:10022000A9020008A9020008A9020008A902000802 +:10023000A9020008A9020008A9020008A9020008F2 +:10024000A9020008A9020008A9020008A9020008E2 +:10025000A9020008A9020008A9020008A9020008D2 +:10026000A9020008A9020008A9020008A9020008C2 +:10027000A9020008A9020008A9020008A9020008B2 +:10028000A9020008A9020008A9020008A9020008A2 +:10029000A9020008A90200080000000000000000F8 +:1002A000FFECC2925D7D05C5EFF305801EF0040FE3 +:1002B00002D0EFF309818D466A4602F16802EFF33E +:1002C00011831EF0100F0CBF2DED108A90B02DE998 +:1002D000FC4F6946DFF828D000F07EFAB0E8FC4F0A +:1002E0001EF0100F0CBFB0EC108A40301EF0040F4F +:1002F0000CBF80F3088880F3098883F31188704766 +:100300000803002408B51E4B1E48DA1CC11E121A31 +:1003100022F00302994288BF0022002100F0B5FCC0 +:10032000194B1A48DA1CC11E121A22F00302994214 +:1003300088BF0022164900F093FB00F027F900F077 +:1003400063FA00F081F9BFF34F8FBFF36F8F4FF067 +:10035000E023D3F8902F22F00102C3F8902FD3F8B6 +:10036000942F22F00102C3F8942FBFF34F8FBFF3F5 +:100370006F8F00F0D2FC00F01BFA00F0E1FC00BF30 +:100380004414002408010024040100240000002477 +:1003900038A80008764A82B0D2F8003423F48023CB +:1003A00043F48033C2F80034724B0193019B002B5D +:1003B00000F3D580019B002B40F3CF806C4BD3F82A +:1003C000182422F4706222F00F0242F00802C3F8EF +:1003D0001824D3F81C2422F4E06242F04002C3F84F +:1003E0001C24D3F81C2422F4E06242F48062C3F897 +:1003F0001C24D3F8182422F0700242F04002C3F803 +:100400001824D3F8202422F0700242F04002C3F8EE +:100410002024594AC3F82824584AC3F83024584A9B +:10042000C3F8382402F50032C3F84024554AC3F813 +:100430002C24D3F8002442F0A852C3F80024D3F8A7 +:1004400000249001FBD5D3F800241101FBD5484BC3 +:10045000D3F800249200FBD5D3F80C2842F0060212 +:10046000C3F80C28D3F8182842F44042C3F81828DF +:10047000D3F818289004FBD53D4BD3F804289104F9 +:10048000FBD5D3F8F4244FF0B04142F00202C3F898 +:10049000F424D1F82C2442F00102C1F82C24D3F822 +:1004A00018289204FBD5384A22211160D3F8102471 +:1004B00022F0070242F00302C3F810242C4BD3F8B9 +:1004C000102402F03802182AF9D1D3F8542422F467 +:1004D000405242F40052C3F85424D3F8582422F472 +:1004E000407242F40072C3F85824D3F8502422F426 +:1004F000E04242F48052C3F85024D3F8502422F44E +:10050000E02242F48032C3F85024D3F8582422F079 +:10051000E04242F08052C3F85824D3F8542422F425 +:10052000401242F40012C3F85424D3F8542422F0A9 +:100530000702C3F85424D3F8542422F03802C3F835 +:100540005424D3F8582422F44032C3F85824D3F862 +:10055000502422F04052C3F8502402B07047D2F821 +:1005600000349B033FF526AF019B013B1DE700BF15 +:1005700000400258F82F9100124040003B02030750 +:100580002F0201018808BF000020005210B52A4C3C +:1005900000200122D4F8003443F00103C4F80034F1 +:1005A000264BC3F80821C4F81004254BD4F80024C6 +:1005B000134043F01003C4F80034224BC4F82C3429 +:1005C000D4F8003423F48023C4F80034C4F8600461 +:1005D00000F07CF8FFF7DEFED4F8D83443F0006377 +:1005E00043F00303C4F8D834D4F8DC34C4F8DC3462 +:1005F000D4F8D434C4F8D434D4F8E03443F080537D +:1006000043F09F03C4F8E034D4F8E834C4F8E83485 +:10061000D4F8EC34C4F8EC34D4F8F03443F01003DC +:10062000C4F8F034D4F8E434C4F8E434D4F8F4343E +:10063000C4F8F43410BD00BF0040025800800051DF +:1006400067EFFEEA0000FF017047FFEC30B4EFF304 +:10065000118400238022EFF3108372B682F3118895 +:1006600083F31088BFF34F8F164B174AD3F8003827 +:10067000118803F4807578B101311180128875B149 +:10068000C2B10023BFF34F8FE4B284F31188BBB132 +:10069000042030BC00F04EB851B10139EDE7002A1A +:1006A000EFD043F48073074AC2F800380123E9E72A +:1006B000002DE6D023F48073024AC2F80038E0E748 +:1006C00030BC70470040025808030024EFF3118249 +:1006D00000238021EFF3108372B681F3118883F336 +:1006E00010880749D1F8003823F48073C1F8003826 +:1006F0000021044B1980D3B283F31188FFF7A6BF02 +:10070000004002580803002430B5EFF311840023A1 +:100710008025EFF3108372B685F3118883F3108878 +:10072000036823EA0101E3B20A43026083F31188FC +:1007300030BDFFEC82B000221C49B0F57A7F0BD8A7 +:10074000002242F22A51642811D800220A2818D81F +:10075000002208BB02B070470192019B8B4202DD70 +:10076000A0F57A70E9E7019B01330193F5E7019267 +:10077000019B8B4201DD6438E5E7019B0133019366 +:10078000F6E70192019BB3F56E7F01DB0A38DDE7E6 +:10079000019B01330193F5E70192019B5E2B01DD83 +:1007A0000138D6E7019B01330193F6E7AD730100F1 +:1007B000BFF34F8FBFF36F8F4FF0E0230022C3F8DA +:1007C000502FD3F8142D42F40032C3F8142DBFF388 +:1007D0004F8FBFF36F8F704737B50A4D0C462B68AC +:1007E0000BB91C462960019000F0F5F829680198C2 +:1007F00000F088FB14B900232C682B60204603B05E +:1008000030BD00BF0C030024EFF3148343F0040356 +:1008100083F314884FF0E023D3F8342F22F04042C2 +:10082000C3F8342FD3F8882D42F47002C3F8882D12 +:100830007047FFEC0F2810B531DDA0F110041F2C1C +:100840000ADC03F1604303F561430B60012303FA03 +:1008500004F4146000201CE03F2C08D81C4C3038F5 +:100860001C440C60012303FA00F01060F2E75F2CD7 +:1008700004D8184C50381C440C60F3E77F2C04D883 +:10088000154C70381C440C60ECE7952C02D94FF0E5 +:10089000FF3010BD114C90381C440C60E2E7104B47 +:1008A00004280B6003D14FF480331360D2E705288E +:1008B00002D14FF40033F8E7062802D14FF4802329 +:1008C000F3E70F28E3D1074B0B600123EDE700BFEF +:1008D00004E100E008E100E00CE100E010E100E0EC +:1008E00024ED00E010E000E008B54FF0E0232049DF +:1008F0004FF0FF305B6803F00F035A1C03F13823FD +:1009000061339B0041F8040B8B42FBD14FF0E02395 +:100910001849C3F8081D4FF08031C3F8181DC3F8FB +:100920001C1DC3F8201D5301134A03F1604303F556 +:10093000644342F8041B9342FBD1104B0022104940 +:100940000B201A6000F0B6FA00220E49032000F0D6 +:10095000B1FA4FF0E022D2F81C3D23F07F4343F080 +:10096000E043C2F81C3DF02383F3118862B608BD52 +:1009700080E100E00000000800E400E00C03002437 +:10098000090A0008D909000813B5802301AA69469D +:100990000446FFF74FFF20B90F2CDDE9003102DDDF +:1009A000196002B010BD1A6822EA01021A60F8E765 +:1009B00013B5002301AA69460446FFF73BFF20B99F +:1009C0000F2CDDE9003102DD196002B010BD1A689C +:1009D0000A431A60F9E7704708B54FF0E023D3F8EF +:1009E0002C2DD3F8283DEFF3118300238022EFF361 +:1009F000108372B682F3118883F31088AD21014809 +:100A000000F036F908A20008CA6E012A08B508D01D +:100A1000022A0AD01AB9D422086F00F021F8002067 +:100A200008BD0A6F034B1A60F9E70A6F11604A6F3D +:100A3000F8E700BF0C030024FFECC2925D7D05C502 +:100A400018DF88DFCD06CD767CD30CD3D982D912BE +:100A50002C00050A0F14191E232800BFAFF30080D5 +:100A600000B501B400F004F801BC00BDAFF3008094 +:100A700000B5042A60DB00F0030E61F3830E7A4BAD +:100A8000D3E80EF0AFF30080AFF30080AFF3008047 +:100A900011F8013B00F8013BA2F1010211F8013B02 +:100AA00000F8013BA2F1010211F8013B00F8013B03 +:100AB000A2F101022DE9F01F282A07DBB1E8F81F97 +:100AC000A0E8F81FA2F12802282AF7DADFF89CE153 +:100AD0004FEA920BDEE80BF051F8043B40F8043B80 +:100AE00026E0B1E81800A0E8180021E0B1E83800DD +:100AF000A0E838001CE0B1E87800A0E8780017E032 +:100B0000B1E8F800A0E8F80012E0B1E8F801A0E8C8 +:100B1000F8010DE0B1E8F803A0E8F80308E0B1E857 +:100B2000F807A0E8F80703E0B1E8F80FA0E8F80F2D +:100B3000BDE8F01F02F00302002A08BF00BD11F853 +:100B4000013B00F8013B013A08BF00BD11F8013B31 +:100B500000F8013B013A08BF00BD11F8013B00F865 +:100B6000013B00BDAFF30080AFF30080AFF3008026 +:100B700011F8013B00F8013BA2F1010211F8013B21 +:100B800000F8013BA2F1010211F8013B00F8013B22 +:100B9000A2F10102282A35DB2DE9F01FB1E8F81F88 +:100BA00020F8023B4FEA134364F31F434FEA144417 +:100BB00065F31F444FEA154566F31F454FEA164695 +:100BC00067F31F464FEA174768F31F474FEA184875 +:100BD00069F31F484FEA19496AF31F494FEA1A4A55 +:100BE0006BF31F4A4FEA1B4B6CF31F4BA0E8F80F47 +:100BF0004FEA1C4C20F802CBA2F12802282ACDDAB9 +:100C0000BDE8F01F042A97DB51F8043B20F8023BB3 +:100C10004FEA134320F8023BA2F10402BAE711F8AD +:100C2000013B00F8013BA2F1010211F8013B00F881 +:100C3000013BA2F1010211F8013B00F8013BA2F1D6 +:100C40000102042AFFF678AF51F8043B00F8013B9B +:100C50004FEA132320F8023B4FEA134300F8013B0D +:100C6000A2F10402EDE70000400A0008500A000863 +:100C700008B501F0B7FB012000F004F8012008B529 +:100C800000F000F808B500F083FB002A43D010F014 +:100C9000010F034639D0013A03F8011B012A38D964 +:100CA000F0B541EA01259E07ADB22BD0023A23F8F8 +:100CB000025B032A18D95C0745EA054616BF141FD4 +:100CC000144643F8046B224603EB040C072A13D89E +:100CD000E2086FF0070707FB02423C40032A234467 +:100CE00084BF043A43F8046B012A02D9023A23F87C +:100CF000025B02B11970F0BDACEB0207083AC7E91C +:100D00000066E3E7032AD6D8F0E7012AC8D11970B4 +:100D100001E0002AFBD17047704700F009B80020BD +:100D200070470021084601F00BBA04F023BDFFEC28 +:100D3000014801F057BA00BF090C02007047FFECF0 +:100D40003C4C01233C4D8C2204F170062B7083B582 +:100D500000212046FFF799FF032318223749237704 +:100D60003046374B374FC4E905330623E38303F09E +:100D7000D5FD354920463E6003F0DBFB334B01A92E +:100D80006846334E1C6002232B7001F009FADDE93E +:100D9000000103F0DFF9042333603368012B45DDE4 +:100DA0003068800003F0F4F92A4B1860336804605F +:100DB0002048A17F00F008FBA3681E48DB685F6045 +:100DC00001F064FC1B4800F0F1FA1A4800F01AFB2D +:100DD000A36805221A7200221F4B1A6003232B708E +:100DE00000F0C0F806F0A0FD1C4B0BB100F032FB88 +:100DF0001B4B0BB107F0BBFB1A4B0BB100F080FF94 +:100E000001F09CF901F082FB05F093F804230948F6 +:100E10002B7000F01AFB05232B7000F039F8062325 +:100E20002B7000F0AFF801F02FFCFCE733685B009B +:100E3000B2E700BF18030024B403002420A2000876 +:100E4000410D000810030024C4030024CC03002437 +:100E5000B0030024C0030024AC0300245514000890 +:100E60006F850008011D000813B50024FFF759FF26 +:100E7000054B40F67A4264210094044800F0D9F80A +:100E8000204602B010BD00BF299B00086CA20008DC +:100E900013B50024054B4FF40062FE210094044872 +:100EA00000F0E0F8204602B010BD00BF690E000857 +:100EB0007CA20008A52870B505460C461AD8EFF3A9 +:100EC000118600238021EFF3108372B681F311881D +:100ED00083F310881CB9FFF757FD2246074C0848DA +:100EE000F6B240F8354000EBC500426086F3118849 +:100EF000002070BD6FF01500FBE700BF410F000838 +:100F0000E8030024A52808B50CD8094A52F8303067 +:100F10005BB102EBC00252689847064B1A68064B59 +:100F20001A6008BD0022054BF6E71A46FBE700BF32 +:100F3000E8030024C4030024CC030024410F00086C +:100F400008B5EFF3118300238022EFF3108372B60C +:100F500082F3118883F3108836210148FFF788FE59 +:100F600087A20008054B1B682BB1054A126812B90D +:100F70001A8C01321A840020704700BFC403002479 +:100F80000C030024134B10B51A68C2B1124B1B6836 +:100F9000ABB9EFF311848021EFF3108372B681F3C4 +:100FA000118883F31088B2F92030002B09DC00236C +:100FB00013840A4B1B6853B9E4B284F311880020F0 +:100FC00010BD013B9BB21384002BF5D1EFE701F07C +:100FD000B5FAF1E7C40300240C030024B80300248D +:100FE00070B586B005468C200E46CDE9043203F07C +:100FF000CFF80446D0B10021C68303910C99029129 +:101000000B9901910A99DDE904320091294600F01B +:1010100033F8051E05DA204603F0AAF8284606B084 +:1010200070BD2046E56800F077F9F7E76FF00B0533 +:10103000F4E71FB5069C00920A46CDE9013400236F +:101040001946FFF7CDFF04B010BD1FB5079C0294F1 +:10105000069CCDE9003413460A460221FFF7C0FF83 +:1010600004B010BD13B5049CCDE900341346002232 +:10107000FFF7EBFF02B010BD2DE9F347867F8846EE +:101080000546914631461F46DDF828A000F09CF940 +:10109000041E3ADB284606F0030600F0D8F9041EC9 +:1010A0000CDB87B152463946284601F0B5FA041EDA +:1010B00005DB284600F07AF9041E13DA57B12846FA +:1010C00000F0A6F921E032465146284601F0DCF94D +:1010D000041EEEDAAB6B002BF1D03146284601F04E +:1010E00047FAECE70B9B49460A4A2846009600F06F +:1010F00013F8041EE2DB0C9A4146284600F0A0F8E3 +:10110000041EDBDB284600F07DF9204602B0BDE876 +:10111000F08700BF3D1300082DE9F74F04460E4647 +:1011200001929946EFF3118700238022EFF3108399 +:1011300072B682F3118883F31088DFF8FCA0DFF821 +:10114000FC80DAF800500020D8F800300135384A29 +:10115000116888420DDB1068C00003F019F8344AAA +:101160000546002845D1FFB287F311886FF00B00C8 +:1011700039E0012D1168B8BF01250139294053F824 +:1011800021B003EB810EBBF1000F2FD1CEF8004050 +:10119000FFB2E560CAF8005087F31188019BF6B2F0 +:1011A0009DF8302059460320267402F0030266742D +:1011B000C4E90539E38B23F06303134304F14402CC +:1011C000E38300F083F9204684F81CB001F05EFA56 +:1011D000FFF7C8FE1749204603F0ABF90423237735 +:1011E000FFF7D0FE584603B0BDE8F08F013501305F +:1011F000AEE711684FF0000C0D4B490011601A6802 +:10120000D8F8000002EBD272BCEB620F04DB02F0F4 +:10121000AFFFC8F8005094E750F82C000CF1010C17 +:101220001A68C168013A0A4045F82200E7E700BFA2 +:10123000B0030024A4030024AC030024C003002452 +:10124000344B2DE9F74F002914BF894699460746CC +:101250000024154649461822703003F083FB4846A7 +:1012600087F8884003F076FB461C4DBB2C460234C1 +:10127000384606EB840101F08DF906464FEA8408F2 +:10128000002844D000EB080AA8F10808B346043D42 +:10129000C0F800A0484603F05DFB0446B044494650 +:1012A0000134504603F032FB5444D8451BD1002092 +:1012B0004AF8040CBA68D268566003B0BDE8F08FF3 +:1012C00040F2011855F824000028D0D003F042FB6A +:1012D00001307B6B06449E4216D201344445F1D165 +:1012E0006FF00600E9E74BF8044F55F8041F084675 +:1012F000019103F02FFB81460199204609F1010974 +:1013000003F004FB4C44D0E76FF05A00D5E76FF0D0 +:101310000B00D2E79FA2000810B5EFF31184002361 +:101320008022EFF3108372B682F3118883F3108862 +:1013300001F054F9E4B284F3118810BD38B5134BB1 +:101340001C68E38B03F00303022B02D0204600F05D +:10135000ABFBA368012040F20111DB685A6852F828 +:1013600020304BB9E38BA56903F00303022B08D1AE +:101370001146A847FFF786FC01308842EFD10120D3 +:10138000F8E70146284603F0EDF8F8E7C403002427 +:101390000446002208B5E4B2034B2146186800F069 +:1013A000ABFB204601F096F8C403002410B51821C9 +:1013B000044601F0EFF820B1A368DB680360002069 +:1013C00010BD6FF00B00FBE770B506464FF48E7052 +:1013D00002F0DEFE044690B100F0B3FB051E04DA15 +:1013E000204602F0C5FE284670BD04F12400B4601A +:1013F00006F0CBFA2046002503F0C1F9F3E76FF0C1 +:101400000B05F0E7D0E902321A6001225A727047E8 +:1014100038B58468054634B1637A012B04D9013BA1 +:1014200063720023AB6038BD204600F09BFB204672 +:1014300000F032F904F1240006F0ABFA204603F084 +:10144000BDF9204602F094FEEBE700F098BB00F0F7 +:1014500096BBFFEC0023044A044942F833100133E1 +:10146000A62BFAD1FFF740BAE8030024410F000889 +:1014700038B5044618B3C068B0B1EFF31182002349 +:101480008025EFF3108372B685F3118883F31088FB +:101490000C4B00251B68013B03400B48006840F8DB +:1014A0002350D3B283F31188A36B13B1204601F00C +:1014B0005FF82046FFF7ACFF204602F059FE0020FF +:1014C00038BD00BFB0030024C0030024F8B51746A0 +:1014D000194B06460C461D68FFF744FD0FB16B6CB7 +:1014E0003B60D4B1EFF3118300228021EFF310822F +:1014F00072B681F3118882F31088022E11D0032E68 +:1015000014D0012E14D16A6C21680A4300246A6445 +:10151000DBB283F3118800F011F8FFF733FD2046AA +:10152000F8BD21686A6C22EA0102EFE72268EDE764 +:101530006FF01504ECE700BFC4030024184B30B56E +:101540001D6885B0FFF70EFD6C6C284600F0F4FCBA +:10155000E4430440039424B9FFF714FD204605B08A +:1015600030BD03A800F070F8431C014610D0019074 +:1015700003A803F041F80199284600F013F8044647 +:1015800030B1011D284600F09BF8204600F02EF8EF +:10159000039B002BE5D1FFF7F5FC0120DFE700BF3F +:1015A000C403002438B58368EFF31185002280203E +:1015B000EFF3108272B680F3118882F31088002056 +:1015C0009C6974B122798A4206D103F1180130B9BD +:1015D000084602F089FF04E020462468F1E702F0A3 +:1015E0008DFFEDB285F31188204638BD10B5037B21 +:1015F00083B9EFF311848022EFF3108372B682F384 +:10160000118883F310880E4902F04EFFE4B284F390 +:10161000118810BD022B0CD1EFF31184002380221E +:10162000EFF3108372B682F3118883F310880549B3 +:10163000EAE7012BEDD1BDE8104002F099BD00BFF3 +:10164000380900243009002438B505460124214614 +:10165000284602F0E2FF20B90134202CF7D14FF0E8 +:10166000FF34204638BD38B5044600F14C05284605 +:1016700002F03AFF50B904F15405284602F034FF55 +:1016800038B94FF0FF32C4E9112038BD00F0AEFC8C +:10169000EDE700F0ABFCF0E738B5044600F11005CB +:1016A000284602F021FF28B91834204602F01CFF1A +:1016B00018B938BD00F082FBF2E7FFF797FFF4E7B7 +:1016C0002DE9F0410D460978044629B3443002F073 +:1016D000A4FF012807467ED1EFF311860023802264 +:1016E000EFF3108372B682F3118883F31088237F9F +:1016F000F6B2062B12D1297804F1480002F08DFFD2 +:1017000060B12B682046E3656B6823660023A36401 +:1017100000F064FF86F311880026B4E086F3118898 +:10172000A4682978EFF3118200238020EFF310835F +:1017300072B680F3118883F31088A36913B1187906 +:10174000884208D1D2B282F3118833B12A685A6034 +:101750006A689A60E0E71B68F0E7564B1B68FBB1CC +:10176000554802F0C1FE20B9544802F0BDFE0028E1 +:10177000D2D02B6843606B688360EFF31185002340 +:101780008022EFF3108372B682F3118883F31088FE +:1017900004F11801EDB202F087FE85F31188BBE772 +:1017A000EFF3118600238022EFF3108372B682F3E9 +:1017B000118883F310884048F6B202F095FE86F354 +:1017C00011880028D5D1102002F0DAFC0028A3D01F +:1017D00001230373CDE7FFF7C5FB2978A06800F06C +:1017E000C7FB064600282CD0406848B300F0D2FB67 +:1017F00000284BD073684360B2688260F3689B0630 +:1018000004D4297801238B40134383602B68C36081 +:101810006B680361EFF3118600238022EFF31083DE +:1018200072B682F3118883F3108804F14C01F6B28A +:1018300002F03AFE2249204600F064FF86F3118848 +:101840000026FFF79FFBEFF3118800238022EFF3C0 +:10185000108372B682F3118883F31088237F062BDE +:1018600008D12B682046E3656B6823660023A364D8 +:1018700000F0B4FE5FFA88F888F31188002F08D0D2 +:1018800001DA6FF015063046BDE8F0816FF00B0607 +:10189000D7E7237F052B03D10421204600F012FA5D +:1018A000237F072BEFD12B78082BECD1204600F0BB +:1018B000C6F9E8E70C0300243809002430090024A5 +:1018C000E518000807B5019100F072F928B10199F7 +:1018D00003B05DF804EBFFF7F3BE6FF0020003B056 +:1018E0005DF804FB2DE9F04F87B0044602F0D2FD0D +:1018F00003684FF0800904F14C0A019304F1540885 +:10190000B4F922300293EFF31183039FEFF31087B2 +:1019100072B689F3118887F31088E28B0397DFB2E0 +:1019200012F400720AD087F3118802F0B3FD019B14 +:101930000360029B638407B0BDE8F08F50460592B8 +:1019400002F0D2FD059A06460028ECD0E18B059204 +:1019500041F40071E183414602F0A6FDD4F844B0A1 +:10196000B5684BEA0505656487F31188736806F16D +:101970000C01059A307B9847EFF31183049A059385 +:10198000EFF3108272B689F3118882F31088049203 +:101990004146E28B304622F40072E283626C55408D +:1019A00082EA0B02154085EA0B05656402F086FDAC +:1019B000059BDBB283F31188FFF7C0FD304600F0D2 +:1019C00015FBA0E77047FFEC054B10B51C68FFF74F +:1019D000C9FA204600F012F9BDE81040FFF7D2BA6C +:1019E000C403002408B5024B01201B68FFF74AF925 +:1019F000C403002408B58068203002F00EFE0028E1 +:101A0000D4BF0020012008BD0023084A12F833107B +:101A1000814206D102EBC3035878C04300F00100B5 +:101A2000704701330B2BF1D101207047A8A20008A9 +:101A300038B585685AB100231A4A12F8330081423A +:101A400019D102EBC30305F120005C68BCB9EFF3C8 +:101A5000118400238022EFF3108372B682F3118881 +:101A600083F3108805F12000E4B202F0C5FD84F391 +:101A70001188002413E001330B2BDED1E7E7EFF3ED +:101A8000118500238022EFF3108372B682F3118850 +:101A900083F3108802F0A3FDEDB285F31188204690 +:101AA00038BD00BFA8A200082DE9F04386680024D5 +:101AB000104D4FF002092036A04685B0304602F0A6 +:101AC000A8FD6B6873B12F7801A90022CDF80C90A6 +:101AD0003846CDE90138012300F086F93946304611 +:101AE00002F07DFD013408350B2CEAD1002005B051 +:101AF000BDE8F083A8A2000810B5C38B04461B05FF +:101B000015D43AB9806828B1437A012B02D12C3020 +:101B100002F09FFD204600F00BF82046FFF778FC0E +:101B20002046FFF7A0FDE38B43F40063E38310BD81 +:101B300010B5044600F020F82046BDE8104000F043 +:101B4000A8B838B50546382002F022FB044630B16B +:101B50000122002102F011FD0020EC6038BD6FF081 +:101B60000B00FBE710B5C468204600F07AF8204669 +:101B7000BDE8104002F0FCBA243000F065BA002342 +:101B800007B5024601900121184606F0CBFB019AE9 +:101B900000230621012006F0C5FB0023019A06213F +:101BA000022006F0BFFB002003B05DF804FBFFEC51 +:101BB0000346EFF3118100228020EFF3108272B60A +:101BC00080F3118882F310880A4A106860B1002BF4 +:101BD0000EDB094A1268013A1A4050F8220018B187 +:101BE000C2689A4218BF0020CBB283F311887047B5 +:101BF0000020F9E7C0030024B003002438B50446F0 +:101C0000EFF3118500238022EFF3108372B682F385 +:101C1000118883F31088037F043B032B0BD800F05B +:101C20005BFA042307212046638400F041FAEDB2F9 +:101C300085F3118838BD072100F0FAFBF7E710B5EE +:101C4000EFF3118400238022EFF3108372B682F346 +:101C5000118883F3108800F0C1FCE4B284F311888A +:101C600010BD30B103881B0401D401230380002080 +:101C700070476FF01500704710B5FFF7F2FF041EB4 +:101C800005DA644202F006FC04604FF0FF3420469F +:101C900010BDEFF3118200238021EFF3108372B6A1 +:101CA00081F3118883F31088037F052B06D1016C23 +:101CB0000B8801331BB20B8000230364D3B283F380 +:101CC0001188704738B5EFF3118400228025EFF3B7 +:101CD000108272B685F3118882F31088027F052A7C +:101CE00009D1056C2A88013212B22A80002241846F +:101CF000026400F073FCE4B284F3118838BDFFEC99 +:101D0000F8B50024284B294E6020C3E90044284B35 +:101D1000C3E90044274BC3E90044274BC6E900440C +:101D2000C3E9004402F02CFA054648B100F160070F +:101D30002C7528461835314602F0B6FBAF42F7D174 +:101D4000602002F01DFA044658B100F16005022738 +:101D5000174E277520461834314602F0A5FBA542E0 +:101D6000F7D1402002F00CFA044658B100F14005CA +:101D70000027104E277320461034314602F094FBA2 +:101D8000A542F7D1402002F0FBF9044658B100F11A +:101D900040050227084E277320461034314602F0D2 +:101DA00083FBA542F7D1F8BD1809002420090024BF +:101DB00028090024380900243009002410B5EFF365 +:101DC000118400238022EFF3108372B682F311880E +:101DD00083F310880349E4B202F066FB84F31188B0 +:101DE00010BD00BF180900242DE9F74F1546504AD1 +:101DF0001F280746D2F800B00E46DBF808A004D929 +:101E00006FF0150003B0BDE8F08F41B93946504678 +:101E100000F0AEF8044665B916BB0020F2E7002BCF +:101E2000F4D10B68012BF1D0FFF7EEFD0028EDD1C6 +:101E3000E6E739465846FFF7DDFD30B100230122C1 +:101E4000C5E900230223AB60E6E72CB163682B6091 +:101E5000A3686B60E368F6E7C5E90044AC60DBE7C4 +:101E60003568012D11D12A4639465846FFF7E0FD65 +:101E7000054685B9002CD0D020460AF1100102F0A9 +:101E80001DFB2046FFF79AFFC7E700223946584658 +:101E9000FFF7CEFDEDE7D4B9EFF311834FF0800BE0 +:101EA00000930022EFF3108272B68BF3118882F355 +:101EB0001088204802F018FB009B0446DBB283F335 +:101EC000118850B10AF11001077402F0EDFA656053 +:101ED0007368A360B368E3609FE7502002F050F995 +:101EE00014490446C0B1EFF31183EFF3108972B6C1 +:101EF0008BF3118889F3108800F1500220461434C6 +:101F0000CDE9002302F0D0FA009A0A499442019BDD +:101F1000F4D1DBB283F31188EFF311830093EFF375 +:101F2000108872B68BF3118888F310880846C1E7D1 +:101F3000C403002418090024002337B582680193E4 +:101F4000EFF311858021EFF3108372B681F31188CE +:101F500083F3108894692CB9EDB285F31188019848 +:101F600003B030BD217901A802F039FB2468F2E703 +:101F700038B50D46044640B1FEF7F4FF246914B1AC +:101F8000237CAB4203D1FEF7FDFF204638BD246819 +:101F9000F5E7FFEC124B10B51B6843B1114802F096 +:101FA000A3FAE0B91048BDE8104002F09DBAEFF383 +:101FB000118400238022EFF3108372B682F311881C +:101FC00083F310880748E4B202F08EFA84F3118894 +:101FD00028B9182002F0D4F808B10123037510BD08 +:101FE0000C030024200900242809002410B5037DD7 +:101FF00083B9EFF311848022EFF3108372B682F37A +:10200000118883F310880E4902F04EFAE4B284F38B +:10201000118810BD022B0CD1EFF311840023802214 +:10202000EFF3108372B682F3118883F310880549A9 +:10203000EAE7012BEDD1BDE8104002F099B800BFEE +:10204000200900242809002438B50446EFF311853F +:1020500000238022EFF3108372B682F3118883F39A +:102060001088F0B14368E3B1104B00201B68DBB16E +:10207000A3420FD123681BB19A68A1680A449A60F1 +:1020800058B10A4902F03AFA00206060EDB285F3D7 +:10209000118838BD18461B68E9E7044802F024FAA5 +:1020A000F2E76FF01500F1E71B68FFDE400900243E +:1020B00038B50C46074B054653F8311003EBC40303 +:1020C0001B79DB0703D500F015F82C7738BD02F03B +:1020D00025FAFAE72CA20008054B027F10B553F849 +:1020E0003210044602F030FA0023237710BD00BFFF +:1020F0002CA2000810B50B68027CB3B11C7C944282 +:1021000006D25A6862B9C0E900325860086013E02C +:102110001B68F2E7C0E900321060486000200CE064 +:10212000C0E9003210605860F8E74A68002AF1D12F +:10213000C0E90033C1E90000012010BD7047FFEC89 +:1021400037B5124D2C682CB1114802F06FFA0120FE +:1021500003B030BD0F4802F069FA40F2011369463E +:102160004FF60C70ADF800308DF80240019503F089 +:10217000A7FE011E04DA4942074802F057FAE6E7D3 +:10218000064802F053FA2046E2E700BF480900245F +:1021900000A3000823A300084EA300088DA3000895 +:1021A000044B1B680360C3F1105303F500230B605D +:1021B000704700BF04A2000802064FEA10130CD4B7 +:1021C00003F00F03064A52F8232032B100F00F004B +:1021D000012319B103FA00F0906170471030F9E75C +:1021E000C8A300082DE9F04705090446C0F303170A +:1021F00015F0080540F0D2806A4B53F82760002E96 +:1022000000F0CC8000F4402300F00F08B3F5002F5D +:1022100000F0B180B3F5402F00F0AF80B3F5802F10 +:1022200040F0AD80C0F30021FFF7C6FF0121EFF3BE +:10223000118200238020EFF3108372B680F311889F +:1022400083F31088022940F09C8014F4704FC4F38B +:10225000033017D023074FF00F094BBFA8F1080335 +:1022600043464FF0240C4FF0200C9B005CF806E036 +:1022700009FA03F900FA03F32EEA090E43EA0E0302 +:102280004CF806304FEA48090323D6F800E003294A +:1022900003FA09F32EEA030E6FEA030C01FA09F3BD +:1022A00043EA0E0333606ED004F44033B3F5803F4D +:1022B0006BD0B3F5003F0CBF02230023D6F80CE02F +:1022C00003FA09F30CEA0E0E43EA0E03F36080B939 +:1022D00023074FF00F0A4BBFA8F108034346242001 +:1022E00020209B0050F806E00AFA03F32EEA0303CD +:1022F000835101F1FF3EBEF1010F0DD804F440659A +:10230000B5F5006F43D0B5F5406F42D0A5F5806AB2 +:10231000DAF1000545EB0A05B36805FA09F5012075 +:10232000BEF1010F0CEA030C00FA08F045EA0C05B7 +:10233000B56073682FD8A5052DD5034301297360B7 +:1023400013D0E30511D504F00C044FEA88030F20E5 +:1023500004F1B04403F00C03D4F8081498409F40F3 +:1023600021EA00010F43C4F80874D2B282F3118845 +:102370000020BDE8F087022159E7032157E72946ED +:1023800055E700207EE7002398E7012396E7022522 +:10239000C2E70325C0E723EA0003CFE76FF015008B +:1023A000E7E700BFC8A30008C0B2FFF71BBFFFEC00 +:1023B00002064FEA101310D403F00F03084A52F834 +:1023C000233053B11A6900F00F00012303FA00F023 +:1023D000104214BF1846002070470020704700BF0D +:1023E000C8A3000808B504F01BFB04F019FB04F0B7 +:1023F00017FB0D4B186818B90C4B1B681B6873B999 +:10240000002007F075FCEFF3118300238022EFF327 +:10241000108372B682F3118883F31088FEE7BDE85B +:10242000084007F065BC00BF0C030024C40300246F +:10243000F7B50646114D01912F6806F0CFF80199C6 +:1024400004463046FFF734FE0D4B1B681BB106F007 +:10245000D9F82043C4B234B10A4B1A682AB1FA66DB +:102460002A68D26E1A6003B0F0BD2B6807F16C00C9 +:10247000D96E03B0BDE8F04000F0A7B8C403002453 +:10248000B80300240C03002438B5836B0C460546C2 +:1024900011469BB9204601F073FEA863A86BB0B14A +:1024A0000119E86321F00701091A696300F0CCF80B +:1024B000EB8B002043F48053EB8338BD436BA34286 +:1024C000ECD000F055F8AB6B002BE7D1E2E74FF012 +:1024D000FF30F2E7094C08B52368EFF311830023BE +:1024E0008022EFF3108372B682F3118883F3108891 +:1024F00006F0E0F92368D86E00F002F8C403002467 +:102500000146012000B500DF5DF804FB08B5084A6C +:1025100080230849013B42F8041BFBD1064B0BB159 +:10252000AFF3008000F072FBBDE8084001F0BABCD8 +:1025300008010024EFBEADDE0000000038B50A4CF3 +:10254000256806F05FF830B1084B1A6822B1EA66D8 +:102550002268D26E1A6038BD236805F16C00D96E0E +:10256000BDE8384000F031B8C40300240C03002457 +:1025700010B50446806B20B1E38BDB0401D501F07C +:10258000F7FDE38B23F48053E3830023C4E90E3388 +:10259000636310BD38B50731836B044621F007052E +:1025A0007BB1436BAB420ED9C36B2A460021184660 +:1025B000FEF76BFBE26B03462A44E263626B521B3D +:1025C0006263184638BD0023FBE703460A46022033 +:1025D000194600B500DF5DF804FBFFEC70B5054659 +:1025E0000B4C2668FFF778FD284605F0D3FF30B185 +:1025F000084B1A6822B1F2662268D26E1A6070BD6A +:10260000236806F16C00D96EBDE87040FFF7DDBFAE +:10261000C40300240C03002470B5836B06460D46EA +:10262000144623B1C18B01F00301FFF7A1FF2C4435 +:10263000284624F00704611BC6E90E55716300F0BB +:1026400003F8002070BDFFEC90B5C41D83B024F0EA +:10265000070400AF224679B9391DB94228BF39466F +:1026600021F00703191A074B21F0030121448A4284 +:1026700004D10C37BD4690BD0144F1E742F8043B5C +:10268000F5E700BFEFBEADDE7047FFEC38B50025C3 +:10269000C168044645668566C56661B9184B186809 +:1026A00040F2EE23A0F2EE206363C4E90E00BDE821 +:1026B0003840FFF7C9BF406BD4222946A0F1D403AC +:1026C000E06B1844E066FEF7E0FAE36B616BE26EE4 +:1026D0000B4413606369E26E23F00103C2F8843097 +:1026E0004FF08072E36EC3F888206FF01602E36E3D +:1026F0009A62F022E36EC3F8CC50E36E5A6038BDA4 +:1027000004A2000810B5436E044603BB1B4B1A68B5 +:1027100082421DD11A4C236813B9BDE81040084706 +:10272000A3F1D400C2E919132060D4221946FEF7A0 +:1027300097F9236803F1D4021A60124A2368C3F898 +:10274000842080225A604FF08072C3F8882010BD28 +:102750004166D422C16E8166A1F1D400E066FEF725 +:102760007FF9E36E03F1D4021A60064AE36EC3F800 +:1027700084208022E36E5A60E36EE4E7C403002401 +:102780000C0300248927000838B50D4B1C68F02382 +:10279000A56E83F3118862B6636E20469847EFF307 +:1027A000118300238022EFF3108372B682F3118825 +:1027B00083F31088002328466366FFF7A1FE00BF5D +:1027C000C403002410B5846E01F4D873A0F850102F +:1027D00001F00101226822F4D87213432360826E53 +:1027E000936823F001031943916010BD10B5EFF316 +:1027F000118400238022EFF3108372B682F31188D4 +:1028000083F31088FFF7DEFFE4B284F3118810BD74 +:10281000F0B5C36BEFF3118400228021EFF3108237 +:1028200072B681F3118882F31088996E0A6822F0DB +:10283000010002F001050860DE6D5F6E710801EBBA +:102840004701B1FBF6F164293AD9013122F4004085 +:10285000490820F001009A6E10609A6ED16093F8DA +:102860005610234A012902EA000233D142F4C06221 +:1028700093F85700092802D0082830D179B342F4E0 +:102880008052996E0A60986E93F85860416821F4FE +:1028900040510EB141F400514160986E93F8596077 +:1028A000816821F440711EB15E6F0EB141F48071F8 +:1028B00081602A439B6EE4B21A6084F31188F0BDF4 +:1028C000C1F3420221F00F0140F400400904090C59 +:1028D0001143C0E7022908BF42F48062C8E7B3F899 +:1028E0005610B1F5E06F08BF42F08052C9E700BF53 +:1028F000FEE9FFEFC36B9A6E506AB3F8522040EACC +:102900000242C0B20A600022A3F85220704710B5FC +:10291000C06BEFF3118400238022EFF3108372B6B3 +:1029200082F3118883F31088B0F8503039B143F046 +:102930002001E4B2FFF75AFF84F3118810BD23F49D +:10294000907121F00101F4E7C36B9B6ED869C0F36D +:1029500040107047C36B9B6E9962704710B5C06B97 +:10296000EFF3118400238022EFF3108372B682F319 +:10297000118883F31088B0F8503041B143EA020166 +:1029800089B2E4B2FFF732FF84F3118810BD23F05F +:102990008001F5E7C36B9B6ED869C0F3C010704728 +:1029A00038B583685D6940F201139942EC6B05D03C +:1029B000B1F5817F29D06FF0180038BD002A4CD0C6 +:1029C00094F85630FBB1012B4FF480710CBF4FF4DB +:1029D000007300230B4394F858101046002914BFCD +:1029E000402100210B4394F85910002914BF4FF0E7 +:1029F000004100210B4343F030039360E16D01F08F +:102A0000C3FF0020D9E71946E4E732B3936803F027 +:102A10003001302921D1002B01DA616FE9B113F4C3 +:102A2000807117D013F4007F14BF0123022384F8B0 +:102A3000563093681046C3F3801384F85830936877 +:102A4000DB0F84F8593001F0BFFFE0652846FFF73F +:102A5000DFFED6E784F85610EBE76FF01500ACE721 +:102A600010B5C46B94F86000FDF78EFF002294F857 +:102A700060001146BDE81040FEF71CBA38B5C56BC2 +:102A800006492A4695F86000FEF714FA044618B97C +:102A900095F86000FDF78CFF204638BDA12A00089C +:102AA00010B51446926ED3699BB29806A4F85230C2 +:102AB00013D5B4F8501089060FD5204603F05BFFFC +:102AC000B4F852301A0606D5B4F850301B0602D5B9 +:102AD000204603F01AFF002010BD13F00E0FEFD0B8 +:102AE0000E231362ECE710B5C36B144693F859300C +:102AF0002BB1836B9B6922B100219847234618466E +:102B000010BD0121F9E7FFEC38B5C46B0021054683 +:102B1000A36E1960C36B9A6E1D4B9A4203D11022AB +:102B20001C48FDF7F1FDE06EFFF75CFB206FFFF73F +:102B300059FB606F08B1FFF755FBA26E94F858106F +:102B4000536823F47D5309B143F40053536028467E +:102B5000A26E114B11680B401360A26E94F85510D1 +:102B6000936823F4E06323F0010343EA4163936035 +:102B7000FFF74EFEA26E0020136843F0005343F0AF +:102B80000D0313600123A4F8500084F8543038BDBD +:102B900000100140F044025803BEFF33F8B5002690 +:102BA000C46B054684F85460EFF3118780223346E6 +:102BB000EFF3108372B682F3118883F310883146E5 +:102BC0002046FFF7FFFDFFB287F31188EB6B9A6E8B +:102BD0000C4B9A4204D1324610210B48FDF794FD6C +:102BE000A26E136823F00D031360E06EFFF7DCFBA9 +:102BF000206FFFF7D9FB606F18B1BDE8F840FFF711 +:102C0000D3BBF8BD00100140F04402587FB50B491A +:102C1000684601F07BFE0023094D1C4655F8041B55 +:102C200039B15E1C303368468DF8093003F084FCFE +:102C300033460134082CF1D104B070BDE8A300087C +:102C4000F4A30008704738B50A460169044629B163 +:102C50004B69036103B9436100234B61637E207EAE +:102C6000C3F3C00520B9E068007C60F3C30363765A +:102C7000CB6820464A819847637E65F3C303637639 +:102C800038BD37B50446C0680A4680B10368B4F859 +:102C90005E10009121469D6804F11D03A84700289D +:102CA00003DA237C43F00103237403B030BD6FF0DB +:102CB0000400F6E7F0B5047E44B313466401154FF3 +:102CC000E5592E0415D4AE03134E48BF45F0806578 +:102CD0002E40334343EA814301F04F0143F08053D8 +:102CE00043F40043E351437EC28023F04F03194372 +:102CF0004176037E0020094903F110020123D1F837 +:102D00001C4893402343C1F81C38F0BD214623469C +:102D1000D4E700BF000B084000F8F3FF00000840B4 +:102D2000E0B590F818C0144E4FEA4C17BD592B046B +:102D300017D4AB03114B48BF45F080652B401343BC +:102D400043EA814301F04F0143EA8C5343F080533F +:102D500043F40043BB51437EC28023F04F03194329 +:102D60004176007E0123064A83400020D2F81C18D9 +:102D70000B43C2F81C38E0BD0009084000F833FCE2 +:102D800000000840437E8A88DB06C97801F0030111 +:102D900001D5FFF7C5BFFFF78DBFFFEC417E027E77 +:102DA000CB064FEA42124CBF084B094B890713442C +:102DB0001A6822F4001248BF42F080521A60437E23 +:102DC0006FF3C30343760020704700BF000908403B +:102DD000000B084001F07F01F0B5EFF311840023F0 +:102DE0008025EFF3108372B685F3118883F3108882 +:102DF0008618F57CC9B1062922D8012303FA01F10E +:102E00002940D1B101239C460CFA03F73942BE4652 +:102E100010D025EA0E05E4B2F57484F311881C2164 +:102E20004B4322B160331844F0BD2946E9E703F56E +:102E30009273F8E70133072BE6D1E4B284F31188EB +:102E40000020F1E710B5C0B1B9B1EFF31182002352 +:102E50008024EFF3108372B684F3118883F3108813 +:102E60004B7E097EC3F30013184401238B40C17CC1 +:102E70000B43C374D3B283F3118810BD024BD3F854 +:102E80000808C0F30D20704700000840037C61F380 +:102E90004103037400207047EFF311820023802068 +:102EA000EFF3108372B680F3118883F3108808481B +:102EB000D0F8043841B123F00203C0F80438D3B28B +:102EC00083F311880020704743F00203F5E700BF49 +:102ED00000000840084601F04BB910B5182001F079 +:102EE0004FF9044618B118220021FDF7CEFE204606 +:102EF00010BDFFEC70B5EFF3118600238022EFF3D5 +:102F0000108372B682F3118883F31088037CDA068B +:102F100011D50B4CD4F80838DB070CD5D4F804587D +:102F2000052045F0010325F00105C4F8043801F03F +:102F3000F9F8C4F80458F6B286F31188002070BD81 +:102F40000000084070B54B7E05460C465B070CD46C +:102F500022695AB9237E1A485B01195841F0006171 +:102F60001950637E62F38203637670BDD18819B90C +:102F70002046FFF768FEEBE7E388124E5A1E114425 +:102F8000227EB1FBF3F152014B43905943EAC14316 +:102F90000B4900F0604003439351237E5B015A5874 +:102FA00042F004425A50637E43F004036376237E6A +:102FB000002BDAD16B7C062262F307136B74D4E723 +:102FC000000B0840100B0840002882B006DD0023EB +:102FD000034904330A6898420192FADC02B0704750 +:102FE0000010084030B503460B4C1A1D1B1A9942BD +:102FF00000DC30BD2368C3F3072502F8043C02F867 +:10300000035CC3F30745C3F3076302F8025C02F8ED +:10301000013C1346E9E700BF00100840054B064A93 +:10302000C3F8102BD3F8002B42F00442C3F8002B56 +:10303000704700BF00000840180008601023054AD0 +:103040001361054B1169C90601D5013BFAD1032073 +:10305000FDF770BB00000840400D030040F0200069 +:10306000054A064B10611169890601D5013BFAD169 +:103070000320FDF75FBB00BF00000840400D0300C8 +:1030800038B5036904460D4643B1437EDB0606D5D9 +:10309000007E8001FFF7E2FF23691BB938BDFFF70F +:1030A000CDFFF9E729462046FFF7CDFDF4E710B53F +:1030B000EFF3118400238022EFF3108372B682F3C2 +:1030C000118883F310886FF06D01E4B2FFF7D8FF29 +:1030D00084F31188002010BD70B5437E0446DE06DF +:1030E0003CD5037E3E495B015B581D0434D5EFF3AC +:1030F000118500238022EFF3108372B682F31188CA +:1031000083F31088027E5201535823F4004343F0A6 +:1031100090435350334A037E590102EB431318681E +:103120008007FCD58B58EDB243F002038B50207E14 +:103130008001FFF793FF207E2B490122D1F81C3834 +:103140008240204623EA0203C1F81C386FF06D016B +:10315000FFF796FF85F31188002070BDEFF311860D +:1031600000238022EFF3108372B682F3118883F379 +:1031700010881D4DD5F8043843F40073C5F80438A1 +:10318000D5F804381B07FBD5227E0A201749F6B272 +:103190005201535823F4004343F090435350FDF73A +:1031A000C9FA237E124A02215B0120469950D5F8C4 +:1031B000043843F48063C5F80438227ED5F81C38FF +:1031C00002F1100101228A406FF06D0123EA02032F +:1031D000C5F81C38FFF754FF86F31188BCE700BF21 +:1031E000000908400809084000000840000B08409A +:1031F000080B0840F0B5057E1F4F6D01EB5903F039 +:10320000004392B3C688541E3444B4FBF6F4467EA1 +:10321000134306F0030643EAC443012E174E08BFCA +:1032200043EA4473EB51457E047E05F003056401D7 +:10323000012DA35908D1124DD5F80858ED0554BFFA +:1032400043F0805343F0005323F08043033243F0B4 +:1032500004439210A351037E00201B0303F180431B +:1032600003F50123824202DCF0BD0124CFE751F8CF +:10327000204001301C60F5E71009084000090840B3 +:103280000000084010B504466030FFF7B3FF042289 +:10329000637C62F307136374BDE81040FFF7BEBEA2 +:1032A00000221146FFF7EEBFF8B50E6907460C463F +:1032B0005EB90B7E30495B015A5842F000625A50A9 +:1032C000637E66F382036376F8BDF3881BB94B7E99 +:1032D00043F040034B763289F588AA4208D3637ED7 +:1032E000590605D420460021BDE8F840FFF7ABBCE5 +:1032F000637EAD1A6FF38613002D63760ADDE388D3 +:10330000AB4207DC18D13379DB0703D5637E43F08A +:1033100040036376217E194B4A01D258EB1C92B2CE +:10332000B2EBA30F0ADA164A0123D2F834088B4015 +:103330000343C2F83438C7E71D46EBE733892A4612 +:10334000316820461944FFF755FF637E43F00403BC +:103350006376237E23B97B7C052262F307137B749B +:103360003289F3881544ADB2AB423581ACD8637E67 +:103370005A06A9D4B6E700BF00090840180908405A +:10338000000008401A4B024670B5C0688B60EFF32E +:10339000118500238024EFF3108372B684F3118823 +:1033A00083F31088537E13F008031DD114694B6119 +:1033B0003CB9537E13F00406C2E9041109D020463B +:1033C00003E05069416118465161EDB285F31188FF +:1033D00070BD13F01004114603D0FFF765FF3046AF +:1033E000F3E7FFF7AFFDEAE76FF00F00EDE700BF8F +:1033F000000089FF344A00202DE9F047D2F8043854 +:10340000324C23F00103C2F80438FFF727FEE068CE +:1034100018B103682146DB689847FE232C4E2D4FD8 +:1034200000254FF0FF0A4FF01C09E374237509FBD8 +:1034300005483046C7F800A06FF06D01C7F800A23C +:103440000135FFF71DFE98F8793006F1C4006FF0E2 +:103450006D0123F04C0320371C3688F87930FFF7D4 +:103460000FFE98F83D31072D23F04C0388F83D31CD +:10347000DDD1154B4FF0FF3200211548C3F8182855 +:103480004FF00112C3F81C280B22C3F81428C3F80C +:103490001028D3F8002822F4FE62C3F80028402246 +:1034A000238A23F4706323F004032382022323720C +:1034B000FFF736FC402200210748FFF7FBFBBDE881 +:1034C000F047FFF7ABBD00BF00000840D00C002460 +:1034D000300D002408090840F40D002438B5124DC1 +:1034E0000446D5F8043843F40073C5F80438D5F819 +:1034F00004381B07FBD5227E0A200C495201535881 +:1035000043F0804343F400135350FDF713F9D5F80B +:103510000438002043F48063C5F80438637E43F028 +:103520000803637638BD00BF00000840000B084068 +:10353000427E0346D20601D4FFF7D0BF027E064882 +:103540005201115841F40011115000205A7E42F0EE +:1035500008025A76704700BF0009084010B5EFF323 +:10356000118400238022EFF3108372B682F3118856 +:1035700083F3108829B1FFF711FCE4B284F31188BA +:1035800010BDFFF7D5FFF8E72DE9F041437C044675 +:1035900003F0F003202B40F0828000F592756FF06D +:1035A00046012846FFF76CFD6FF0460104F160000C +:1035B000FFF766FD94F83D316FF3C30384F83D31A6 +:1035C00094F879306FF3C30384F87930238A23F0B9 +:1035D00001031B051B0D43F440532382637D13F04D +:1035E000600F05D004F115012046FFF74AFB39E0D2 +:1035F000B4F81770B4F81910B4F81B200FFA87FE4E +:1036000094F816C008B216B2BCF10C0F26D80FF20F +:10361000080858F82CF000BF4D360008073700089E +:103620005D3600085F3700085D360008FD3700088A +:103630004138000841380008493800086738000858 +:10364000E5350008E535000865360008207C4607AA +:1036500004D5022A02D11E0600D517B3237C43F0FD +:1036600001032374237CDB0716D594F878302846B1 +:103670008C495B015A5842F400125A5094F8793040 +:1036800043F0080384F87930FFF728FF237C43F0E8 +:1036900001032374FFF7C2FC0023A4F85E30BDE8E9 +:1036A000F08103F01F03012B2AD0022B0CD0002B3A +:1036B000D4D10029D2D1C0F30013C0F34000A177C8 +:1036C00040EA4300607715E001F07F03062BC5D880 +:1036D000C3EBC3030F064FF002024FEA83034CBF54 +:1036E000603303F5927323445B7EC3F3C0036377B7 +:1036F0000023A37704F11D012046FFF7C3FDB1E7C6 +:103700006777A777F6E7207C4607A7D5002AA5D1DB +:1037100003F01F03022B17D1002F7FF463AF01F0DA +:103720007F0006283FF65EAFC0EBC0000E064FEAF2 +:1037300080004CBF603000F592702044FFF72EFBF4 +:103740002046FFF7ADFD8DE7002B7FF44BAF012F37 +:103750007FF448AF034662F304132374F0E7267C3A +:1037600070077FF57BAF002A7FF478AF03F01F036B +:10377000022B12D1002F3DD101F07F00062839D84D +:10378000C0EBC0000E064FEA80004CBF603000F571 +:1037900092702044FFF7CCFED2E75BBB012F03D130 +:1037A00046F010062674CBE7022F23D1CBB20BBB19 +:1037B000090AA37C0139042914D8DFE801F0030BBE +:1037C0000D0F1100012262F30303A374237C43F065 +:1037D0002003C2E70222F6E70322F4E70422F2E71D +:1037E0000522F0E76FF30303A374237C43F0010386 +:1037F0002374EBE731077FF531AFF3E6DA067FF4A8 +:103800002DAF50EA06037FF429AF7F2F3FF626AF96 +:10381000637C03F00F03022B3FF420AF224AE17DCB +:10382000D2F8003823F4FE6343EA0113C2F80038EB +:103830001E4B228A134009B143F4827323827FE72F +:10384000DB067FF40BAFCDE6217C4F077FF506AF9B +:10385000DE067FF403AF5EEA00037FF4FFAE012AC9 +:103860007FF4FCAEBEE6227C51077FF5F7AEDA06A8 +:103870007FF4F4AE50EA06037FF4F0AE04F11501D4 +:103880002046FFF7FEF900287FF4ECAE218AFFB254 +:10389000074A0A401FB142F402722282E2E642F471 +:1038A0008072FAE70009084000000840FBF0FFFFC3 +:1038B000F7F0FFFF2DE9F04F85B0DFF8B0B2DBF88D +:1038C0001440DBF8182042F4403343F440732340A3 +:1038D000144023F0E96323F4E02323F47D7323F001 +:1038E0000103CBF8143000F0AB8025030FD5DBF8D3 +:1038F0001868DBF81C381E40360C40F0AC80DBF852 +:103900001838FF21984A1B0C002B40F09D8066035D +:1039100012D5964BD3F81858D3F81C281540AAB2E4 +:103920000192002A40F02C81D3F81838FF21904AE8 +:103930009BB2002B40F01281002C12DA8B4A01213D +:103940008C4DD2F80438284623F00103C2F804381D +:10395000FDF7F4F9E86820B1026852690AB1294616 +:10396000904721050AD58349C86818B103681B69C7 +:1039700003B1984700217F48FDF7E0F9E20659D5E9 +:103980007A4B1D6A05F00F09B9F1060F52DC05F4F8 +:10399000F012B2F5002F00F09681B2F5402F00F042 +:1039A000A081B2F5802F45D1C5F30A15002D41D075 +:1039B000DFF8C0811C2606FB0986D6F83471002F7B +:1039C00040F06C8196F83CA1BAF1000F40F06281A2 +:1039D000D6F830717B7C03F0F003102B40F05A8155 +:1039E000402DAB4607F11D00A8BF4FF0400B1FFA5A +:1039F0008BF10191FFF7F6FAA5EB0B00FFF7E4FA64 +:103A000096F83D31022238466AF3820386F83D314A +:103A10007B7C62F307137B740199A7F85E10FFF7B4 +:103A2000B3FD1C2303FB098898F83D316FF3820333 +:103A300088F83D31504B1C4200F06981FFF7DAFCF9 +:103A4000002005B0BDE8F08FD80701D510681160DF +:103A50005B08203258E70027464DF30741D5424B1B +:103A60004FEA471959F80320DBF8143802EA030833 +:103A700018F0010F1FD001233B4A17F0FF0A49F845 +:103A800002306B7C42D103F0F003602B13D1D5F8E8 +:103A900034215ABB95F83D3162F3820385F83D31FC +:103AA00095F83D3113F0040105D1FFF7B7FA6B7CAF +:103AB00061F307136B7418F0020F03D002232A4A34 +:103AC00049F8023018F0080F0BD06B7C03F0F003BC +:103AD000202B02D12846FFF757FD0823224A49F838 +:103AE0000230760807F10107B7D110E751462348A5 +:103AF000FFF7A9F895F83D3120496AF38203A1F553 +:103B0000927085F83D31FFF71DFAC9E703F00F0306 +:103B1000022BD0D11C2000FB0AF005EB000ADAF8DA +:103B200034210AF59C7A32B99AF8053062F382039F +:103B30008AF80530BFE700F5927000212844019013 +:103B4000FFF781F89AF8053001986FF38203014678 +:103B500028468AF80530FFF7F5F9ACE7DD0700D510 +:103B600011605B082032E4E6080B084000000840C2 +:103B700008090840D00C002400108000F40D002437 +:103B8000DFF8C8814FF00009DFF8C4A1A8F1600593 +:103B9000019BD8076DD56B4A4FEA491BD2F8103804 +:103BA000D2F8346801225BF80A7002FA09F2324254 +:103BB000029218BF43F080031F4017F001030393E4 +:103BC00038D0029B5FFA89F21C2126EA03065D4B7E +:103BD00001FB0251C3F83468012360314BF80A300D +:103BE0006B7C002A4ED103F0F003502B0DD12846F8 +:103BF000FFF75AFB95F8793013F0040105D1FFF770 +:103C00000DFA6B7C61F307136B742A7C910611D556 +:103C10004C486FF34512AB7CD0F8041803F00F0E3C +:103C20006FF3030301F0700141EA0E11C0F80418AC +:103C30002A74AB743A0702D508234BF80A30FB0606 +:103C400006D541462846FFF72FFB10234BF80A30D4 +:103C500038060ED5039B4BB9029B4146284626EAFF +:103C60000306384BC3F83468FFF71EFB80234BF87C +:103C70000A30019B09F1010908F11C085B08019356 +:103C800086D159E603F00F03022BD3D12846FFF764 +:103C90000BFBCFE72846FFF797F9C2E63889FE8885 +:103CA0003B68361A1844AE42A8BF2E461FFA86F863 +:103CB0004146FFF797F9A81BFFF786F93989884431 +:103CC000A7F80880B6E6204A527C02F0F002102ADB +:103CD0007FF4B0AED3F8002B42F08062C3F8002B23 +:103CE000A8E6194D082105F11500FFF77BF995F9B4 +:103CF0001530002B08DBB5F81B302BB16B7C012293 +:103D000062F307136B7495E66B7C0222F8E7A30459 +:103D10007FF5D3AD0B4AD2F8003923F4FF6323F0CB +:103D2000070343F04003C2F80039D2F8043843F4E3 +:103D30008073C2F80438D36823F4705343F4C0533B +:103D4000D360BAE500000840D00C0024300D0024F8 +:103D50000809084038B50B4CE060214603681B6831 +:103D60009847054618B10023E360284638BD752002 +:103D7000FCF71EFE01212046FFF78EF80223237276 +:103D8000F3E700BFD00C002470B50446EFF31185B3 +:103D900080260023EFF3108372B686F3118883F335 +:103DA0001088FFF727FBEDB285F311880E4D2046F2 +:103DB000236829465B689847EFF311840023EFF3EB +:103DC000108372B686F3118883F310887520E4B2ED +:103DD000FCF7DAFD00212846FFF75EF80846E960A7 +:103DE00084F3118870BD00BFD00C002470B52B4D3A +:103DF000E86808B1FFF7C8FFEFF3118600238022BF +:103E0000EFF3108372B682F3118883F310880021D8 +:103E10002248FFF741F875200C462972FCF7B4FDE3 +:103E2000752021462246FDF745F81D4BFF204FF037 +:103E3000FF32F6B2C3F80809C3F8080BC3F8280923 +:103E4000C3F8280BC3F84809C3F8480BC3F868093E +:103E5000C3F8680BC3F88809C3F8880BC3F8A8092E +:103E6000C3F8A80BC3F8C809C3F8C80B4FF48060A7 +:103E7000C3F81048C3F81448C3F83448C3F81C48C2 +:103E8000C3F81828FFF7EAF8FFF7D8F86B7C64F35B +:103E900003036B7486F3118870BD00BFD00C00243F +:103EA000000008408F4AF8B5D2F80C3823F00073B0 +:103EB00043F08073C2F80C38D2F80C385901FBD5A6 +:103EC00089484027FEF78EF98848FEF78BF9884825 +:103ED000FEF788F9874EFFF789FF874B4FF4F4729E +:103EE00000211846FCF7D1FE8449024603464FF0F4 +:103EF0001C0C42F8601B01464260FE22C27402752F +:103F000000220CFB02141C335E64196504F1780571 +:103F100094F8794044F010046C70D4B2013283F804 +:103F20005C4064F07F04072A83F848406C786FF3A4 +:103F300001046C70A3F84A70E3D100231C274025CC +:103F4000DAB2C0F82461C0F830111C3080F82021AA +:103F500080F80C2107FB0312013392F83D41072B37 +:103F60006FF3010482F83D41A0F80E51E8D1002220 +:103F700063497520FCF79EFF002803DABDE8F8408E +:103F8000FFF734BF5F4C80235F4DA360E36843F0CD +:103F90004003E3600320FCF7CDFB2369002B01DB2A +:103FA000013DF7D1236943F001032361564B554C82 +:103FB0002269D20701D5013BFAD103200025FCF785 +:103FC000B9FBA36B142043F48033A36300F0AAF879 +:103FD0002368322043F0C0032360E36823F00053DA +:103FE00043F08043E36000F09DF8C4F8005ED4F82D +:103FF00000384FF4806023F4C053C4F80038D4F87C +:10400000003843F00303C4F8003840F20123636230 +:1040100003F59203A3624933C4F804314933C4F869 +:1040200008314933C4F80C314933C4F810314933ED +:10403000C4F814314933C4F81831FFF70FF8FEF70C +:10404000FDFF4FF0FF33C4F81058FF21C4F8145897 +:104050002E4AC4F83458C4F818382D4BC4F81C58EC +:10406000186820330028B4BF4FF00840002043F800 +:10407000200C43F8105C43F8181C9342F0D1254BF8 +:104080000022FF2024491C682033002CB4BF4FF0CD +:104090000844002443F8204C43F8102C43F8180C33 +:1040A0008B42F0D1174B14489A614FF0FF325A609F +:1040B00059691A4A21F07F4121F47C0121F47C41A5 +:1040C00021F0FF010A4300215A61154A9A618122B9 +:1040D0009A60FEF7E1FEFFF78DF97520BDE8F84024 +:1040E000FCF766BC004002580BAC08000CAC0800A2 +:1040F0000AAE090064A40008D00C002448A40008FB +:10410000B538000800000840400D0300E0090840F1 +:1041100000090840000B0840E00B08400AFCB0F81A +:1041200010380C0082B0002209490092009B8342A3 +:1041300001D302B070470192019B8B4203D9009BCF +:1041400001330093F2E7019B01330193F4E700BFD1 +:10415000AD7301000A460146034808B500F052F865 +:10416000024B186008BD00BF80A40008B80E0024F0 +:10417000024B0146186800F0C7B800BFB80E002413 +:10418000024B0146186800F01BB900BFB80E0024AE +:10419000024B0146186800F070B900BFB80E002449 +:1041A000F8B50D460446164600F05AF805F11F030F +:1041B0006168AA19082523F00F03012622F00F02D7 +:1041C000A3F11007D01B01441038C4E9011743F8CC +:1041D000105CA1684E60A3F1080143F8080CA2F13D +:1041E00008004D60E060204642F8085C53F8083C47 +:1041F000E2683343536000F05FF82046BDE8F840C2 +:1042000000F052B801F10F03A2F5A27223F00F03E0 +:1042100070B5541818464FF4A27200211D46E41AD6 +:1042200003F5A276FCF731FD034600F1200200F50C +:10423000A071A2F110009A6110321033D8618A4245 +:10424000F7D1284600F007F8284622463146FFF706 +:10425000A7FF284670BD0122002100F099B9FFECAC +:10426000104B37B51C6805464CB101A900F0AAF9FE +:1042700001980028D4BF0020012003B030BD04F015 +:104280003DFB00280CDB284604F05CFA002801DB2B +:104290000120F2E700F0FEF80368002BF3DCF7E7FB +:1042A0002046EAE70C030024024B1B680BB904F01C +:1042B00095BA70470C03002438B5054608680C46CB +:1042C00000F015F8421C05EB021205EB0015AB6976 +:1042D00023B1196811B12068814205D39460C4E903 +:1042E000023203B1DC6038BD1A469B68F0E7B0F5D6 +:1042F000800F07D203090020012B00D8704701303E +:104300005B08F9E71220704770B505460C46A9B165 +:10431000FFF7A6FF98B9EFF3118300228021EFF396 +:10432000108272B681F3118882F31088D5F840218B +:10433000DBB22260C5F8404183F3118870BD54F8A8 +:10434000043CA4F1080123F0010344F8043C54F8B0 +:10435000083CCA185068C60713D4CB58D2E90206E5 +:104360001344B06008B1D668C660126854F8080CEF +:10437000104444F8080C5A6802F0010202435A60E3 +:104380001A4654F8043CCB1A5868C00710D4D3E935 +:104390000210816009B1D868C860196854F8080C27 +:1043A00008441860516801F0010101435160194649 +:1043B0002846FFF781FF2846BDE87040FFF774BF2D +:1043C000F8B506460F46EFF3118300228021EFF384 +:1043D000108272B681F3118882F310880022D0F81F +:1043E0004041DBB2C0F8402183F31188002C39D161 +:1043F000002F35D007F1170525F00F05AF422FD854 +:104400003046FFF72DFFB5F5800F32D22846FFF773 +:104410006EFF06EB00108469FCB12268A368AA4213 +:1044200029D3E26893600BB1E268DA602368581B15 +:104430000F280CD92344611960514D6025605A68DA +:1044400002F00102024330465A60FFF735FF63680D +:10445000083443F0010344F8043C3046FFF724FFDE +:104460002046F8BD2568214630462C46FFF74CFF14 +:10447000BCE71220CDE71C46CEE713B50191FFF74C +:104480009FFF044618B1019A0021FCF7FEFB20466D +:1044900002B010BD08B500F099FA08B1143008BD9B +:1044A0000048FCE7BC0E0024002303600B6813B92E +:1044B0000860486070474B681860FAE70B6802466E +:1044C0008BB180B1834208D11A680A604A689A4267 +:1044D00009D100234B6070472BB118461B689342EB +:1044E000FAD100F00BB8704703682BB11A6802606C +:1044F00002B9426000221A60184670470A680368D1 +:1045000052B14BB14A689A424FF0000215BF196888 +:104510004860016002601A6018467047002303601B +:104520004B6843600A6812B90860486070471860B9 +:10453000FBE7002343600B68036013B9C1E9000087 +:104540007047586008607047D0E9003232B90B609C +:1045500033B94A600023C0E9003370471360F7E7BE +:104560005A60F7E707B504460191009200F03AFA65 +:10457000DDE90010A047FCF785FB30B1B2F5004F34 +:1045800003D212B20280002070476FF0150070470E +:1045900008B530B1B2F5004F03D212B2028000204C +:1045A00008BDFFF777FF162303604FF0FF30F7E7F2 +:1045B00028B121B1038800201BB20B6070476FF057 +:1045C0001500704710B5FFF7F3FF041E05DA6442CB +:1045D000FFF760FF04604FF0FF34204610BD1F2935 +:1045E0009FBF012303FA01F103680B439ABF0360E5 +:1045F00000206FF0150070471F299FBF012303FAA9 +:1046000001F103688B439ABF036000206FF015002F +:10461000704700230360184670471F299DBF00683C +:10462000C84000F001006FF0150070470FB41FB5CF +:1046300006AB53F8041B0191039304F00FF8039A9F +:104640005030019900F079F805B05DF804EB04B042 +:10465000704770B5044630B300F0D4F80121201D36 +:10466000002600F022F8012104F1500000F01DF8AE +:10467000012104F19C0000F018F8D4F8E85025B9A5 +:10468000204600F0C7F8304670BDB5F844309B07AF +:1046900007D50121284600F008F836EA200628BF91 +:1046A00006462D68EBE70646EDE7F8B54368054694 +:1046B0000F46002B3EDBB0F844309B073AD500F0A4 +:1046C000BCF86C69FCB1EE69B44207D1284600F031 +:1046D000D3F8EC696969641A2046F8BD2B6A9C42DC +:1046E00026D1361B32462146686803F0E9FC0028D3 +:1046F0000DDA95F8463043F0020385F84630FFF7AF +:10470000C9FE04686442284600F0B6F8E4E70444B1 +:10471000361A0FB1002EE5DC6B692644EB61B4421A +:10472000D4D0EB695A1CEA6114F8012B1A70F6E731 +:104730000024E8E76FF00804CEE730B589B00446FE +:104740000D46014603A8019200F0C6F8204600F08D +:1047500074F82946019A03A800F066F90546204638 +:1047600000F08AF8284609B030BD08B5FDF784FA94 +:10477000002803DABDE80840FFF78CBE08BD38B555 +:104780000122044600212C30FFF702FF4FF0FF35D5 +:10479000002304F130006563C4E9453300F03CF8C0 +:1047A00004F17C00C4F8805000F036F804F1C80031 +:1047B000C4F8CC50BDE8384000F02EB838B50446F7 +:1047C0002C30FDF759FA0023C4F81831D4F81451ED +:1047D0006DB904F13800FFF7C8FF04F18400FFF75A +:1047E000C4FF04F1D000BDE83840FFF7BEBF284643 +:1047F00050F8083BC4F81431FFF7B7FF2846FFF71D +:10480000B7FCE3E710B50446204603F09BFF002801 +:10481000FADB10BD03F0E2BF08B500214FF0FF3313 +:104820000122083001814360FFF7B2FE002803DA5D +:10483000BDE80840FFF72EBE08BD70B5044604F081 +:1048400099F80546E368984212D004F1080630460C +:1048500003F078FF031E07DAFFF71CFE0368042B42 +:10486000F5D08C2BF3D05B422BB90123E56001E03E +:10487000238A0133238270BD10B5044604F07AF810 +:10488000238A012B0ED1002304F1080023824FF06C +:10489000FF33E36003F0A2FF002805DABDE8104013 +:1048A000FFF7F8BD013B238210BD01210069FFF72E +:1048B000FCBE38B504460D462169284600F0B6FD19 +:1048C000013003D0E3680133E36038BDFFF7E2FD58 +:1048D0000368042BF0D0F8E7094B03604B6963B120 +:1048E000B1F84430074A13F4807F074B18BF1346D2 +:1048F00083600023C0E903317047034BF8E700BF32 +:10490000B3480008AB4800086B540008421E11F879 +:10491000013B02F8013F002BF9D17047034610B567 +:1049200092B10A44084604460130904203D1002265 +:1049300020461A7009E010F8014C03F8014B002CD6 +:10494000F1D1401A013810BD084610F8013B002B88 +:10495000FBD1F6E703461A46013311780029FAD154 +:10496000101A704710B5024404464B1E904208D0FE +:1049700013F8011F00F8011B0029F7D1121AFCF7E8 +:1049800084F9204610BDFFEC0E4B002230B5D3E970 +:1049900000548C4209D1C561836823F4805323F00D +:1049A0000F0319438160002030BDA94202D1C161CB +:1049B0002146F1E7013208331F2AE8D1C1614FF4E3 +:1049C0008051E9E788A40008C06970471FB500203E +:1049D00001A903F05DFE0028ACBF0298002005B0DD +:1049E0005DF804FB2DE9F0410A4D2B6843B90A4CF0 +:1049F0000A4E0B4FDFF82C80B44203D101232B6009 +:104A0000BDE8F08154F8043BBB42F5D34345F3D2F3 +:104A10009847F1E7C00E002430A8000830A800082D +:104A20000000000830A8000807B5009200220B46DD +:104A3000114600F003F803B05DF804FB2DE9F04FD8 +:104A40008FB005460026DDF8609093F800A0BAF11B +:104A5000000F00F0EF83BAF1250F08D00133029365 +:104A60002B68514628460136CB46984725E193F8F6 +:104A700001A09A1CBAF1250F0292F1D04FF0000864 +:104A80000A22474644463F2C4CD8BAF12B0F3ED061 +:104A900013D8BAF1200F3CD0BAF1230F3FD0AAF1BE +:104AA0003003DBB2092B4FD8E0054EBF02FB0838BC +:104AB00044F0800402FB073707E0BAF12D0F2BD03A +:104AC000BAF1300FEBD144F00104029B13F801ABB3 +:104AD0000293BAF1000FD6D1AAF14503022B72D886 +:104AE0000AF1200A44F400545FFA8AFA14F4807F31 +:104AF00008BF4FF00608BAF1650F5FFA88F140F081 +:104B00008280013144F48044C9B2002283E044F041 +:104B1000020444F00404D8E744F00804D5E744F064 +:104B20001004D2E7B4F5007FB9D3BAF17A0F2AD0D6 +:104B3000BAF1740F27D0BAF16A0F21D124F480643E +:104B4000A4B244F42064C0E7BAF12A0F0FD1E00503 +:104B500059F8043B02D523EAE378B6E7002BA7BF58 +:104B600044F080041F465F4244F08804ADE7BAF188 +:104B70002E0FDAD1E00500F15D8344F48074A4E7E0 +:104B8000BAF16C0F09D1A30548BF44F4006424F4C2 +:104B90008064A4B244F4007497E7BAF1680F09D1B5 +:104BA000600548BF44F4006424F40074A4B244F4E3 +:104BB00080648AE7BAF1700F02BF24F42064A4B2C3 +:104BC00044F4007488E7AAF16503022B8ED9BAF188 +:104BD000630F00F0A8810AF0DF03532B40F0C98176 +:104BE000CB469D4B5BF8049BB9F1000F08BF99467B +:104BF00014F4807F484614BF41464FF0FF3100F067 +:104C000036FC804698E1BAF1660F7FF47EAF0A4623 +:104C100044F400440F2109F107090F2908A829F0DD +:104C2000070B28BF0F21BBEC020B00F035FB9DF8F2 +:104C3000243003F00902012A42D0A20743D414F021 +:104C4000040F0CBF4FF000094FF0200913F00C0FB8 +:104C500043D0B9F1000F14BF04230323BB420CDA85 +:104C60002107A7EB030709D4B8462B682021284663 +:104C70009847B8F10108F8D13E440027B9F1000F78 +:104C800004D02B6849462846013698479DF82430C1 +:104C900004F40054714A13F0080F714B0CBF904696 +:104CA0009846A6EB080909EB080618F8011B69B934 +:104CB0003C46002C40F0B8823E44D946029BC4E6F4 +:104CC0004FF02D09C2E74FF02B09BFE70CB1203997 +:104CD000C9B22B6828469847E5E7C3B2DDF820A0A3 +:104CE0000193604B019A1C421BD1134608A904335F +:104CF0000B44019919B113F8011930292CD01AF17C +:104D0000040F2EDB92452CDABAF1000F44F4004474 +:104D100002DB019B9A4528DA0AF10108019BA3EB0B +:104D2000080823B2002B0393B6BF2AEAEA730523CF +:104D30000133B9F1000F00D00133B8F1000F17D0E3 +:104D400008F101021344BB42B4BFFF1A002714F05C +:104D5000090F1CD13B4615E00199481EC1B20191D3 +:104D6000C7E7019B03F1FF38DBE74FF00008D8E706 +:104D7000E20648BF0133E6E7202128460493904726 +:104D8000049B013B2A68002BF6D13E441F46B9F133 +:104D9000000F04D02B684946284601369847230760 +:104DA0000CD4B94604E009F1FF3930212846984770 +:104DB0002B68B9F1000FF6D13E444F46039B002B00 +:104DC00052DA2AEAEA79C8F10003AAEB090204934D +:104DD000019B09F1FF3904999A4237BF08AB4FF0A4 +:104DE0003008D31893F80580731C894503932B680A +:104DF0001CDAE40606D5B9F1FF3F03D12E2128467F +:104E00009847039ECA450BD19DF82530352B20D8F5 +:104E100006D19DF8243013F0100F08BF4FF0310871 +:104E200001362B6841462846984741E741462846C7 +:104E300005929847B9F1FF3F059A07D1B31C2E217F +:104E40002846059203932B689847059A0132039EE2 +:104E5000BEE74FF03108E3E788A5000880A5000809 +:104E600084A5000800C0FFFF9DF8251028463129C1 +:104E70001EBF9DF8243023F010038DF824302B68DA +:104E80009847B8F1000F2B683DDD02364FF001095D +:104E90002E2128469847C8452B6821DA14F4005F74 +:104EA0002B68284614BF452165219847BAF1000FA9 +:104EB00004DB31D19DF82430D9062DD5CAF1000A82 +:104EC0002D212B68284698473021BAF1090F25DC9F +:104ED0002B682846984704362B680AF13001A2E770 +:104EE000019A284601364A4588BF09F1380209F17E +:104EF000010994BF30216A445FFA89F988BF12F82A +:104F0000131C9847C7E7E00601D40136C6E72E21F7 +:104F1000284602369847C1E72B21D2E70131AAF192 +:104F20000A0AC9B2D1E7CB464FF001080DF12009BA +:104F30005BF8043B8DF8203022070FD509EB0804FD +:104F40004C450DD14644B3E6013F2B68202128464D +:104F500098474745A4EB0706F6D8EFE7BC19F8E7F2 +:104F60002B68284619F8011B9847002FE8D0013F0D +:104F7000E6E7BAF1640F04F4206302D0BAF1690FD6 +:104F800078D1B3F5206F63D109F1070929F007093A +:104F9000CB46D9F804105BF8080B24F4805900299B +:104FA00029F0100906DA404249F4805961EB4101C9 +:104FB0001FFA89F919F4807F06D0B8F1000F03D1E8 +:104FC00050EA010300F0C28008AC0A23224600F038 +:104FD00035F9041BE4B219F4807F019400F0B88025 +:104FE00029F0010A44451FFA8AFA80F2B48044F29B +:104FF00010025FFA88F309EA0202102A03D129F0AD +:1050000011091FFA89FA1AF0100F00F0AE8004F1AE +:1050100038026A4412F8192C302A40F09E802AF493 +:10502000C04A2AF0100A1FFA8AFA1AF0080F40F054 +:10503000AD801AF0010F06D0BB4280F2C480FB1A8B +:1050400003EB0408FBB2A3EB06095FFA89F998E0C9 +:10505000CB46A3055BF8040B4FEAE0719DD46205D3 +:105060009BD5230555BF40F3C03140F3C01100B2BA +:1050700040B292E7B3F5206F1DD109F1070929F07D +:105080000709CB46D9F804105BF8080B24F0060991 +:10509000BAF1580F1FFA89F945D0AAF16F03DAB2B5 +:1050A000092A47D8092B45D8DFE803F04E254444A8 +:1050B000444415444436A10509F1040BD9F8000015 +:1050C00001D50021E2E714F48061DFD0220554BF4E +:1050D00080B2C0B2F5E724F016040A231FFA84F95F +:1050E00019F4807F05D0B8F1000F02D150EA010217 +:1050F0002CD008AC6AE7029B1B78562B0AD1029B86 +:105100000133029343681A68079201682846FFF743 +:105110008BFCD2E549F0100919F0100F01D049F4C9 +:1051200080491023DCE7E30601D549F4C0494FF478 +:105130000473D5E72B6828462521023698472B684B +:10514000514628469847B8E50823C9E7444642E750 +:105150002346CA4657E7234655E71AF4804F01D144 +:10516000013300E00233DBB25FE741F206021AEAE4 +:10517000020F3FF45AAFF3E72B682021284601368F +:10518000984709EB0603DBB2BB42F5DBBB42B4BF79 +:10519000FF1A00271AF0100F22D02B683021284662 +:1051A00098471AF4804F10D10136C146A14529DC39 +:1051B000A8EB0400A045B8BF002006444CBB019BEF +:1051C00033441E4674E5A0463DE71AF4005F06F13D +:1051D00002062B6814BF5821782128469847E4E737 +:1051E00041F206031AEA030FDFD01AF0020F06F1AC +:1051F00001062B6814BF2B2120211AF4805F18BFF1 +:105200002D21EAE72B683021284609F1FF3998471C +:10521000CCE7631E0EAA284652FA83F2DCB22B6852 +:1052200012F8181C9847C9E72B6820212846013C32 +:1052300098473EE530460FB0BDE8F08F2DE9F843C2 +:1052400013F400791C4606460F461CBF23F4007475 +:105250004FF0010915464FEAE478304639462246B8 +:10526000434604F079F9092AB4463B4606460F4600 +:1052700009DC3032A44505F8012B73EB0803ECD2AE +:105280002846BDE8F883B9F1000F01D03732F1E7C5 +:105290005732EFE7FFECC2922DE9F74F10EE904A3C +:1052A00007460E4614F000441CBFB1EE400B01242B +:1052B000B5EE400BF1EE10FA11D121EAE1720530A2 +:1052C000302144F00204FBF7E0FC0025BB1900226A +:1052D00030465A713C713D6003B0BDE8F08FB4EECA +:1052E000400BF1EE10FA02D744F00804EDE7B0EEFF +:1052F000C07B9FED436BB4EE467BF1EE10FA02DD0E +:1053000044F00404E1E79FED406BB4EEC60BF1EE10 +:1053100010FA5DD5404908230F2501209FED3C6B15 +:1053200091ED107B20EE077BB4EEC67BF1EE10FA18 +:1053300005D500FA03FCB0EE470BA5EB0C05013BCD +:105340000839B3F1FF3FEBD132B125EAE573013300 +:105350001A449642A8BF1646304B03EBC60393EDA2 +:10536000007B30EE070B9FED2A7BB4EEC70BF1EE0E +:1053700010FA04DBB2EE047B013580EE070B07F177 +:105380000508DFF8A0A0DFF8A0B051EC100B04F086 +:10539000FBF86FF0040389460090DB1B0193019B2F +:1053A00043449E4292DD52465B460098494604F0D3 +:1053B000D3F800F1300C59465046009299460A2223 +:1053C000002308F801CB04F0C7F882468B46E6E7D5 +:1053D000134908230F25012091ED107B20EE077B58 +:1053E000B4EEC67BF1EE10FA04DB00FA03FCB0EE7B +:1053F000470B6544013B0839B3F1FF3FECD1A3E70C +:10540000FFFFFFFFFFFFEF7F00003426F56B0C432B +:105410000080E03779C3414358A6000890A50008F2 +:1054200010A600080080C6A47E8D030037B50A468A +:105430008DF8070004460D460DF10700012100F02C +:1054400022F8002804DC4FF0FF34204603B030BDC2 +:105450000A2CFAD195F846305B07F6D5012128468B +:10546000FFF723F90028F0DAEDE700207047024645 +:10547000014410B58A42134603D01C780132002C37 +:10548000F8D1181A10BD2DE9F84380460F4616468C +:1054900042B9FEF7FFFF4FF0FF34092303602046B7 +:1054A000BDE8F883B2F844309B0706D4FEF7F2FF5C +:1054B000092303604FF0FF3418E053693BB90A46F3 +:1054C0000146706802F0FCFD041EE8DAF2E71046BF +:1054D000FFF7B3F9304600F04EF800280DDA4FF030 +:1054E000FF343046FFF7C8F9002CD8DA96F846307A +:1054F00043F0020386F84630D1E7D6E906502D1A6C +:10550000202D01D11F2F1CD8BD42414628BF3D464A +:105510002A46A7EB0509FBF7A3FAF369B26908EB82 +:1055200005042B449342F36104D2B9F11F0F14D93F +:105530004F4607E000213046FFF7B7F80028F4DABD +:10554000CDE744463A462146706802F0B9FD00288E +:10555000C5DB0444A4EB0804C3E7B9F1000FF9D09C +:1055600021464A46F06908EB0704FBF779FAF3692C +:105570004B44F361EEE710B5044630B9FEF78AFFFD +:10558000092303604FF0FF3010BD4369F3B1FFF70B +:1055900054F9206A6269904213D0E36994F8471085 +:1055A0001B1A2046C4E907220022591A84F8472012 +:1055B000012200F00DF8002803DA2046FFF75CF91D +:1055C000E0E72046FFF758F90020DDE71846DBE763 +:1055D00000F000B870B504460D461646FFF7CBFF45 +:1055E000002802DA4FF0FF3070BD204600F010F8BE +:1055F0000028F7DB002332462946606884F84730EC +:1056000002F03FFC01304FF0FF3018BF0020EBE705 +:10561000426932B1B0F844309B0702D50121FFF74F +:1056200044B800207047022901D100F063BB012972 +:1056300001D100F0C3BB704708B500F085FBBDE8A1 +:10564000084000F001BCFFEC38B50F4D04462B7844 +:1056500013F0FD0F09D1C20707D500F081FB002828 +:1056600003DB0A4B02221A7004E02B78012B02D9CB +:105670004FF0FF3038BDA307FAD500F0F1FB00284A +:10568000F6DB024B0122EEE7C50E0024CC1300240A +:1056900010B5084C606004F001F9FFF7D5FF002851 +:1056A00004DB054A13680133136010BD6368002BE7 +:1056B000F1D1FAE7D0130024C80E002408B5FFF793 +:1056C000E7FFA0F120035842584108BD73B50446D6 +:1056D00001AE00256420FFF7DBFF002807DB013562 +:1056E00006F8010B042DF5D1019B0020236002B0C8 +:1056F00070BDFFEC70B5094E04460D463378022BA1 +:1057000001D100F053FB3378012B05D12946204607 +:10571000BDE8704000F0BABB70BD00BFC50E0024EC +:1057200010B5114C236801331DD062680F4B9A42AB +:1057300019D90F4B9B6803F1006303F500339A42BC +:1057400011D204F00BF904F0D7F8FFF775FF04F05D +:10575000E1F804F0A5F8204604F01AF92046BDE867 +:10576000104004F0DBB910BD00000208FFFF010883 +:10577000B000002410B500230B4C54F8232022B1B4 +:1057800054F82320013A44F823200133042BF4D1A8 +:10579000064B1B7833B9A36823B9022004F0A0F9A3 +:1057A0003223A36010BD00BFD0130024C40E002418 +:1057B000024BD860DA68002AFCD17047D01300246D +:1057C0002DE9F04FAF4B8FB000250646DFF8BC82C5 +:1057D0001D700395D8F8084004F07AF8DFF8C0A2ED +:1057E0000EB1CAF80060DFF8BC924FF0FF37CAF87C +:1057F000085089F80050012004F062F926B1DAF867 +:105800000030002B00F068820020FFF741FF049079 +:10581000049B002BF2DB012004F042F9049B213BA6 +:105820001F2BE8D801A252F823F000BFAD580008A2 +:10583000C3580008B1590008F7570008F757000887 +:10584000F7570008D3590008F7570008715A0008A5 +:105850002F5B00085D5B00089D5B00081D5C000875 +:10586000BF5B0008ED5B00087B5C000887590008FF +:10587000F7570008F7570008F7570008F7570008D0 +:10588000F7570008F7570008F7570008F7570008C0 +:10589000F7570008F7570008F7570008F7570008B0 +:1058A000F7570008F75700082B5900080220FFF7A8 +:1058B00005FF002800F00582039B43F001030393DA +:1058C00061E04FF47A70FFF7E3FE051EC0F2F98144 +:1058D0000220FFF7F3FE002800F0F381681E042881 +:1058E00000F2EF81DFE800F0030B0E111400042139 +:1058F0006548FFF7FFFE039B43F00203DFE7042147 +:105900006248F6E704216248F3E704216148F0E7C2 +:105910001C252846043504F05CF80421069006A8EE +:10592000FFF7E8FE2C2DF4D1E5E701250220FFF773 +:10593000C5FE002800F0C581039B03F00303032B81 +:1059400040F0BF8101234FF0000B022089F80030A6 +:1059500004F0A6F804F00DF8584604F01EF80446CA +:1059600040BB022089F8000004F0AAF8D8F80830FB +:10597000A34226D8039B002443F0040389F8004087 +:105980000393CAF80840039B3E4A03F00303032B2A +:10599000137808BF002613B93F4B1B78137041F2F0 +:1059A0001203022106A8ADF81830FFF7A3FE22E784 +:1059B0000025BBE7584629460BF1010B03F0F3FF26 +:1059C000CAE7204604F005F8013040F05381043462 +:1059D000CCE73220FFF75CFE051EC0F2728115F0A5 +:1059E000030240F06E812B19D8F808108B4200F2A8 +:1059F0006881B5F5807F00F26481DFF8A0B0594678 +:105A0000AA4214D1C820FFF759FE002800F059819E +:105A100024B9224B4FF0FF321F681A6025F00305AE +:105A20002544AC4215D1039B43F0080347E74FF4EC +:105A30007A70CDE90012FFF72BFE0490049800283D +:105A4000C0F23F8104980099019A01F8010B0132DC +:105A5000D6E7DBF80010204603F0B5FF204603F040 +:105A6000B8FF5BF8042B904240F004810434D8E77F +:105A70000220FFF723FE002800F023810025AB461B +:105A800042E000BFC50E0024B8A60008B000002404 +:105A9000B4000024B8000024CC130024CC1200244D +:105AA000D0130024C40E0024002D3BD1791C39D022 +:105AB00006978B494A68C2B98C461346082003F002 +:105AC000010E5B08BEF1000F07D083F06D4383F435 +:105AD000380383F4034383F020030138EFD101320C +:105AE0004CF8043BB2F5807FE7D106A8002210F8FD +:105AF000013B013283EA0B03042ADBB251F8233065 +:105B000083EA1B2BF3D10435D8F80830AB42CBD84D +:105B1000042106A8CDF818B0FFF7ECFD039B43F075 +:105B20001003CCE6284603F054FF0690C1E700239B +:105B300005A80593FFF7CAFD002840F0C2800220A7 +:105B4000FFF7BCFD002800F0BC80059803F04BFF78 +:105B50000421069006A8FFF7CDFD14E7002305A851 +:105B60000593FFF7B3FD002840F0AB800220FFF75C +:105B7000A5FD002800F0A5800598820740F0A180CF +:105B8000082800F29E8003F083FF0421069006A8F7 +:105B9000FFF7B0FD039B43F0400390E60220FFF7C0 +:105BA0008DFD002800F08D8003F020FF0421069079 +:105BB00006A8FFF79FFD039B43F080037FE60220CA +:105BC000FFF77CFD00287CD006A9142003F014FF09 +:105BD00005460421059005A8FFF78CFD294606A877 +:105BE000FFF788FD039B43F4807368E60220FFF70C +:105BF00065FD002865D020223A49172506A8FEF742 +:105C0000B1FE042105A80595FFF774FD294606A8F5 +:105C1000FFF770FD039B43F4007350E66420FFF729 +:105C200037FD00284DDBC5B21E2D4AD80220FFF7F4 +:105C300045FD002845D04FF4D07003F0CAFE8346DE +:105C40004FF4D27003F0C5FE274B9B4539D1274B4B +:105C5000984236D1DFF898B04FF4D07045EA0B0B7C +:105C6000594603F0B0FE4FF4D07003F0B2FE584531 +:105C70003FF489AE41F2121393E64FF47A70FFF7C6 +:105C80001DFDF0B17B1C0DD141F2120306A80221CB +:105C9000ADF81830FFF72EFD64200FB0BDE8F04FCF +:105CA000FFF786BD039B03F01B031B2B09D139466D +:105CB000002003F088FE002003F08BFE8742E3D033 +:105CC000D8E741F21233022106A8ADF81830FFF7E9 +:105CD00011FD002303938EE50FB0BDE8F08F00BFE8 +:105CE000CC0E0024A0A60008FFECC2925D7D05C585 +:105CF00000ECC29238B50F4B0F4C002808BF184675 +:105D000003F0A0FA0D49206003F0ACFA0C4B00B18F +:105D100018604FF0FF320B4D432118682A6002F0E3 +:105D200060F9002805DB28602068BDE83840FEF7F0 +:105D30001FBA38BD8CA30008E4130024BCA60008D9 +:105D4000E01300247800002410B5044C206801F012 +:105D500022FF4FF0FF33236010BD00BF7800002406 +:105D600013B50F4C2368002B0FDA0E4B4321186834 +:105D700002F037F9002803DA4FF0FF3002B010BD0F +:105D8000094B20601868FEF7F3F901220DF10701B5 +:105D9000206802F060F90128EED19DF80700EDE7D8 +:105DA00078000024E0130024E4130024024B0A4688 +:105DB0000146186802F084B9780000241E4B70B5C3 +:105DC000002808BF184688B003F03CFA1B49064675 +:105DD00003F048FA054638B31849002003F042FAA8 +:105DE00030B303F0ECF804464321284602F0F9F8FA +:105DF000031E13DB124D69462B6003F069FA029B08 +:105E00002146684623F4B87343F030030293FEF74B +:105E1000BBFD6A460021286803F05FFA304608B0EF +:105E2000BDE87040FEF7A4B94FF4E134054DDBE75F +:105E30004FF4E134D8E700BF8CA30008BCA60008EB +:105E40007C000024BEA6000810B5044C206801F0B8 +:105E5000A2FE4FF0FF33236010BD00BF7C00002482 +:105E6000094B07B5186800280BDB01220DF107016B +:105E700002F0F1F8012804D19DF8070003B05DF8A5 +:105E800004FB4FF0FF30F9E77C000024F8B504462E +:105E900046184FF47A75094FB44208D1F8BD012273 +:105EA0002146386802F00CF9012804D0013D002D8C +:105EB000F5D10134F0E74FF47A75FAE77C0000245D +:105EC00003464FF604720846934210B513D04FF6BE +:105ED0000C72934212D04FF60172934226D1FAF718 +:105EE0001EFF002804461FDA6442FEF7D3FA04605E +:105EF0004FF0FF3418E003F0FBFEF2E70B78012BC4 +:105F000005D14C78012C05D0022C08D064B16FF07B +:105F10001504E9E74968807801F05AFBE1E74B682E +:105F20000024186801F0D2FB204610BD6FF0180461 +:105F3000DAE708B500F080FDBDE8084000F012B8CF +:105F4000002070471046704708B54AB14B688A6810 +:105F500003F0050313438B6013B1086902F000FCE2 +:105F6000002008BD00234FF4DB720249024802F012 +:105F700046BA00BFD4A60008C9A6000813B5044657 +:105F8000A36B20460191DB6A984701990028F7D05E +:105F9000A36B20465B6A02B0BDE8104018472DE9AC +:105FA000F74F458C0446B0F9263088462DB24FF0A5 +:105FB000800B01920135AB42D8BF0025A38C1BB2E8 +:105FC000AB420AD0638C2DB2A26A00201BB202F849 +:105FD0000380658403B0BDE8F08F019B002B30D0B7 +:105FE000EFF3118AEFF3108772B68BF3118887F302 +:105FF0001088A38C1BB2AB421ED1E27802F0FF09DD +:10600000E2B90121A26B20466170926A904704F1C7 +:106010001A0002F05FFBA26B06464946926A2046D0 +:1060200090475FFA8AFA8AF31188E37863B9002E01 +:10603000C4DA6FF00300CDE70026F2E76FF07F06C9 +:10604000EFE76FF00A00C5E76FF07F00C2E72DE9C8 +:10605000F74F836880460E4601925C6904F12C0973 +:10606000484602F037FB051E1FDB00254FF0010BF1 +:10607000019B9D4204D2E378DBB10DB96FF07F053F +:10608000A36B012120469B699847E28D238E12B2B3 +:106090001BB29A4206D1A36B1B6A1BB10022204699 +:1060A00011469847484602F05BFB284603B0BDE81E +:1060B000F08F238EE28D19B212B28A421ED0626B2B +:1060C0000133525C1BB2B4F932109942D8BF00239D +:1060D0002386E36813F4E07F05D00A2A07D113F082 +:1060E000400F18BF0D22013506F8012BC0E70D2A1D +:1060F000F9D113F4807F18BF0A22F4E7002DBFD135 +:10610000D8F80830002B4BD0D8F8005015F04005D7 +:1061100049D1EFF3118A8023EFF3108772B683F32E +:10612000118887F31088A26B294620465FFA8AFA05 +:1061300092699047E18D228E09B212B2914227D125 +:10614000A26B0121204692699047E18D228E09B20F +:1061500012B2914202D08AF3118889E7E278A2B99B +:1061600004F11C0084F802B002F0B4FA8AF311883A +:10617000002803DBE378002B3FF47AAFE378002BB1 +:106180007FF47CAF6FF003057AE76FF07F00EDE7F7 +:106190008AF31188A36B012120469B69984767E722 +:1061A0006FF050056CE76FF00A0569E72DE9F041E3 +:1061B00083685E6906F11805284602F08BFA041E12 +:1061C00023DBF378002B36D13378013313F0FF074C +:1061D00034D0012F2DD1EFF3118800238022EFF36B +:1061E000108372B682F3118883F3108833795FFAD3 +:1061F00088F86BB9B36B30461B689847041E07DA02 +:1062000088F31188284602F0ABFA2046BDE8F081F9 +:10621000B36B30469B689847041EB36B03DA5B6828 +:1062200030469847ECE79B6901213046984788F350 +:1062300011883770E6E76FF07F04E3E76FF017042B +:10624000E0E7F7B50E4600F1400700F1500557F8BA +:10625000044B8CB16368A26843F0180333401343C6 +:10626000A3604BB101A92069FEF7A2F9019B002BA5 +:1062700002DC206902F074FAAF42E8D103B0F0BD4D +:106280002DE9F84383680E4615465C6904F11E0843 +:10629000404602F01FFA071E4EDB002D4FD004F1DE +:1062A0004002002352F8045B002D34D1103304F176 +:1062B000200944F8236004EB83034846736102F02D +:1062C00039FA638CB4F926201BB201339A42D8BF45 +:1062D0000023A28C12B29A4225D1484604F12C091F +:1062E00002F03EFA484602F025FAE28D238E484637 +:1062F00012B21BB29A421EBF736803F001031D4322 +:1063000002F02EFAE37893B145F0180529462046AD +:10631000FFF797FF0DE00133042BC3D100236FF08B +:106320000F07736105E0756805F00405D5E7002DDA +:10633000ECD1404602F014FA3846BDE8F8837369A0 +:10634000002BF6D01D607561F3E7FFEC2DE9F047F7 +:10635000836880460F4616465D69464B1B6823B12D +:10636000EB78ABB16FF07F0425E002F07FF90028F5 +:10637000F6D105F1200A504602F0ACF9041E1ADBF2 +:10638000EB7803F0FF018BB3504602F0E9F9E9E73F +:10639000EFF3118400238022EFF3108372B682F3AF +:1063A000118883F3108807EB0608B84506D1E4B2DC +:1063B00084F3118834462046BDE8F0872B6917F82E +:1063C000011BD80703D50D2905D11A0705D4284686 +:1063D000FFF7D4FDE9E70A29F9D113F0240F03D020 +:1063E0000D212846FFF7CAFD0A21F0E7D8F8002062 +:1063F000B146AB6B284682F040089B6AC8F3801810 +:106400009847B9F1000F01D1344623E02B6917F802 +:10641000011BD80703D50D290AD11A070AD4424611 +:106420002846FFF7BCFD041E10DB09F1FF39E8E741 +:106430000A29F4D113F0240F01D10A21EFE74246D3 +:106440000D212846FFF7ABFD041EF6DAB14501D257 +:10645000A6EB09046A8CAB8C12B21BB29A4204D030 +:10646000AB6B012128469B6A9847504602F078F9A9 +:10647000A1E700BF0C0300242DE9F04700F120083C +:1064800004460E46404602F025F9051E1DDBEFF3DB +:10649000118700238022EFF3108372B682F31188F4 +:1064A00083F31088E37803F0FF0553B3638C6FF038 +:1064B0007F05A384FFB287F311881E4F002DD7F804 +:1064C00000902CDA404602F04BF92846BDE8F087F0 +:1064D000A36B0121204684F801A09B6A9847484697 +:1064E00002F0F8F8A36B054600219B6A2046984706 +:1064F000002DDFDB628CA38C12B21BB29A42E7D173 +:10650000D8E74FF0010A04F11A09F3E74FF47A7063 +:1065100002F0BAF93B68A3EB0903B34206D2A36BBE +:1065200020461B6B98470028F0D0CBE76FF073052F +:10653000CBE700BFEC1300244FF0FF332DE9F0410F +:106540008B6005460B790C462BB14B6943F0010378 +:106550004B6105230B610122002104F1200004F1AD +:106560001A07FEF70AF80122002104F12C00FEF7B9 +:1065700004F80122002104F11800FDF7FEFF0022BB +:10658000384604F11C061146FDF7F7FF002230469D +:106590001146FDF7F2FF0122002104F11E00FDF774 +:1065A000ECFF0021384602F0B5FC0021304602F035 +:1065B000B1FC234628464FF4DB720249BDE8F041A6 +:1065C00001F01DBFF4A6000810B504460121FFF735 +:1065D00038FEA3783BB1002304F11C00A370BDE892 +:1065E000104002F0BDB810BD10B504460421FFF7FD +:1065F00028FE63783BB1002304F11A006370BDE804 +:10660000104002F0ADB810BD70B583680E46154657 +:106610005C69A36B1B69F3B9B6F58D7F0DDAB6F52E +:106620008A7FC0F2BC80A6F58A73052B00F2B78082 +:10663000DFE803F0799BB5B5A2ACB6F5427F36D062 +:1066400040F209339E424ED040F207339E420AD0B8 +:106650006FF018008FE0984710F1190FDCD0002878 +:1066600000F09F8087E0EFF3118100238022EFF399 +:10667000108372B682F3118883F31088228EE38D23 +:1066800012B21BB29A420ADCE38D228E1BB212B206 +:106690009B1ACAB282F311882B6000206BE0228E15 +:1066A000E08D12B2B4F9323000B2121AF0E7EFF313 +:1066B000118100238022EFF3108372B682F31188D8 +:1066C00083F31088A28C638C12B21BB29A4203DC53 +:1066D000638CA28C1BB2DAE7A28C608C12B2B4F984 +:1066E000263000B2E1E7EFF3118100238022EFF3BF +:1066F000108372B682F3118883F31088628CA38CA6 +:1067000012B21BB29A4206DAA38C628C1BB212B28E +:106710009B1A013BBDE7628CA08C12B2B4F9263003 +:1067200000B2121AF4E7EFF3118600238022EFF390 +:10673000108372B682F3118883F3108835F0020259 +:1067400007D1E38D2386A36B1B6A13B11146204644 +:106750009847013D012D04D8638C2046A384FFF7A0 +:1067600043FFF6B286F3118897E742F21071204694 +:10677000FFF782FE70B970BD002D02DA6FF01500D0 +:10678000F9E7A368002BF9DAA56086E74FF0FF333D +:10679000A36082E710F1190F3FF45AAFEBE76FF0F7 +:1067A000180040F201139E420BD0B6F5817FE2D172 +:1067B000002DE3D02B68E3606B682361EB686361B5 +:1067C0006BE7002DDAD0E3682B6023696B606369A7 +:1067D000EB6062E770B504460D46EFF311860023C7 +:1067E0008022EFF3108372B682F3118883F310884E +:1067F00081F00103C37089B91821FFF722FD637886 +:1068000023B104F11A00657001F0AAFFA3782BB13F +:10681000002304F11C00A37001F0A2FFF6B286F37E +:10682000118870BD10B5044600211A3001F0E3FF55 +:10683000002104F11C0001F0DEFF012104F1200021 +:1068400001F0D9FF012104F12C0001F0D4FF04F183 +:106850001E000121BDE8104001F0CDBF70B5836876 +:1068600005465C6904F11806304601F063FF2378A1 +:10687000012B06D9013B2370304601F071FF002047 +:1068800070BD0021A36B204621709B6998472B683F +:106890005B0604D44FF47A612046FFF7EDFDEFF379 +:1068A000118500238022EFF3108372B682F31188E2 +:1068B00083F31088A36B2046DB68984723791BB9C4 +:1068C000A36B20465B689847EDB285F3118820469C +:1068D000FFF77AFE2046FFF7A5FFCDE7436913F0E7 +:1068E000010302D00A44914201D10020704783681D +:1068F000002B04DD0B78032B03D01A2B03D00131BE +:10690000F1E70A20704707207047F8B500250446D4 +:106910002F46628CAEB2A38C12B21BB29A4210D137 +:10692000628CA38C12B21BB29A4204D1A36B0021D9 +:1069300020469B6A9847EEB12046BDE8F840FFF735 +:1069400053BEA36B2046DB6A98470028E8D0A38C8F +:106950002046A16A1BB2A26BC95C526A9047A38C05 +:10696000B4F9262001331BB29A42A38400DCA78429 +:106970000135CEE7F8BD2DE9F341C58D0027B0F90B +:10698000323004462DB2B8460135AB42D8BF00259F +:10699000A36B2046DB69984700282FD0268E36B29D +:1069A000AE4220D0A36B01A920465B699847012223 +:1069B0008DF803000DF103012046FFF78FFFAE4273 +:1069C0008046E5D0E38D01379DF803101BB2626B62 +:1069D000BFB2D1542BB20135E385B4F93230AB42AA +:1069E000D8BF0025D4E7A36B1B6A002BDAD00122A5 +:1069F000B4F93210204698470028D3D017B120466A +:106A0000FFF7E2FDB8F1000F06D04146A06801F0A3 +:106A100019FF2046FFF706FF02B0BDE8F081FFEC4A +:106A200008B5044B186818B103689B6803B1984710 +:106A3000002008BD84000024002070477047C36B0D +:106A400093F85430002B0CBF6FF07F00002070478C +:106A5000704700207047C36B93F85500032894BF1C +:106A600000200120704770B5036806460D469B68FC +:106A70009847044660B1C5802846FDF781FB05466E +:106A8000206028B9336821462C463046DB68984799 +:106A9000204670BD806890F8543013B10121FFF793 +:106AA00099BE704700218068FFF794BEF8B5044690 +:106AB000EFF3118500238022EFF3108372B682F387 +:106AC000118883F31088C66E8C30FDF70DFD48B336 +:106AD00094F85530A1220227013B84F855304168D3 +:106AE0000B681A7020229F715A7000229A70DA7017 +:106AF0001A715A71DA7194F859705A721F720A2316 +:106B000008613046CB8001230B7133681B699847BD +:106B100094F85930EDB203F0030384F8593085F34B +:106B20001188F8BD6FF00B00F2E770B50D46044612 +:106B300058B151B1086808B1FDF71AFB236829461E +:106B40002046DB68BDE87040184770BD10B590F86E +:106B50005430044693B1002180F85410FFF73AFEF8 +:106B6000E06E03685B689847206F03685B6898472E +:106B7000606F0368BDE810405B68184710BD70B5D2 +:106B80000C468568EFF3118600238022EFF3108313 +:106B900072B682F3118883F3108800212846FFF72C +:106BA00019FE2846FFF7D2FF0023F6B26B84AB84B0 +:106BB00086F3118823685B6923B120460121BDE873 +:106BC0007040184770BD2DE9F04184680D46002CD7 +:106BD00049D02046FFF7BAFF3220FDF7A3FAE16E55 +:106BE00029B12B6828465B6898470023E366A16FAC +:106BF00021B16868FFF799FF0023A367264604F1D7 +:106C000030074FF00008D6F8E81021B1606FFFF7A9 +:106C10008CFFC6F8E8800C36BE42F4D1616F29B112 +:106C20002B6828465B68984700236367EFF311865B +:106C300000238022EFF3108372B682F3118883F36E +:106C4000108804F18C08D4F88C7077B9F6B286F30A +:106C50001188216F21B12B6828465B689847276708 +:106C600000236384A384BDE8F0814046FDF73CFC2B +:106C700041680029E7D0206FFFF757FF94F855309F +:106C8000013B84F85530DEE72DE9F84F84680D4666 +:106C9000804621654B6840219C606868FFF7E3FEF1 +:106CA000A067002879D03E4B0122C36028462B689C +:106CB00094F8B0101E68032341F08001B047E066ED +:106CC00030B96FF0120429464046FFF77CFF61E0BF +:106CD000846001222B68284694F8B4101E680223B1 +:106CE00041F08001B04720670028EAD0846000228C +:106CF0002B68284694F8B8101E680223B0476067D6 +:106D00000028DED004F1E40604F58A7A4FF0000B87 +:106D10008460B1464021606FFFF7A5FE70600028D7 +:106D20003BD0A6F808B006610C3656F8082C1D4B6F +:106D30005645D360EED104F1C4064FF0800A6021BD +:106D4000206FFFF790FE706038B30661164A7368D3 +:106D5000DA60EFF3118BEFF3108772B68AF31188C4 +:106D600087F3108804F18C013046FDF79DFB94F801 +:106D700055205FFA8BF3013284F8552083F3118894 +:106D800008364E45DBD12B685C691CB101212846D1 +:106D9000A04700242046BDE8F88F6FF00B0492E76F +:106DA0003D6A0008257400088775000837B5044659 +:106DB000154608461A466946002300F0E3FC23689E +:106DC0002A4669461B682046984703B030BDFFEC51 +:106DD0002DE9F34190F8543004460E468B4204D11D +:106DE0000025284602B0BDE8F081FFF7AFFE002E77 +:106DF000F6D0012E41D1002204F19C03E06E114631 +:106E00000193FFF7D3FF051E33DBE26E0221019BE6 +:106E100094600022206FFFF7C9FF051E29DB226F57 +:106E20003146019B94603246606FFFF7BFFF051E3D +:106E30001FDB636F264604F13007DFF844809C6057 +:106E4000D6F8E810C1F80C80606F03681B6998479A +:106E5000054670B994F856300C360133BE4284F8BA +:106E60005630EDD10121204684F85410FFF7B2FCD2 +:106E7000B7E72046FFF76AFEB3E76FF01505B0E706 +:106E8000257400082DE9F0410F461178D0F80880EC +:106E900011F0600C5488D8F878509088D6887BD14F +:106EA0005378063B052B00F2CC80DFE803F003CAE1 +:106EB0004139634AD378022B24D0032B2BD0012BEA +:106EC00040F0BF802C6800F059FC00F1100223460E +:106ED00050F8041B904243F8041BF9D10288122099 +:106EE0001A80B0424FF001032946A8BF30462B71EB +:106EF000E880786803681B699847002809DA00234E +:106F00006B8106E008F19C01286800F071FC002804 +:106F1000E7DABDE8F0812968907800F0F3FBF6E746 +:106F2000002940F08E80E1B24046FFF751FFEEE7C6 +:106F3000802940F086802B6898F854201A70012030 +:106F4000CFE701297DD198F85430012B79D1D8F8B9 +:106F5000A030984202D00133984272D1002C70D1F7 +:106F60004046FFF7F3FD98F854104046FFF730FF16 +:106F70000020B6E7812964D198F85430002B60D105 +:106F8000D8F8A030984202D00133984256D1002C54 +:106F900054D12B681C70D2E7BCF1200F51D152782C +:106FA000203A032A4DD8DFE802F014022D3DA12932 +:106FB00047D1D8F8A030984243D1D8F85E200720B6 +:106FC0002B681A60B8F862209A8098F864209A7149 +:106FD00087E7212935D1072E33D1D8F8A020904258 +:106FE0002FD143B11A68C8F85E209A88A8F86220A9 +:106FF0009B7988F86430D8F86830002BB8D000202E +:107000009847B5E721291CD1D8F8A030984218D16B +:1070100004F00304D8F8683088F85840002BA7D053 +:107020000120EDE721290CD1D8F8A030984208D1F1 +:10703000D8F86830002B9BD00220E1E76FF02000E9 +:1070400067E76FF05E0064E700230B81406F4968DB +:10705000C388CB8003681B691847FFEC2DE9F04714 +:107060000446EFF3118800238022EFF3108372B6F9 +:1070700082F3118883F3108800F17C094846FAF7FF +:10708000E3FF94F85D30002B53D094F85B30002B75 +:107090004FD104F1940AD4F894502DB95FFA88F8CE +:1070A00088F31188BDE8F0876A682B891068178912 +:1070B0001844B4F93220FF1AE38D0133BFB29BB2FA +:1070C0009342A8BF00230022218E96B209B28B42C0 +:1070D00018D1228E12B2934206D1B4F93210012295 +:1070E0002046013900F066F916B12046FFF76CFA28 +:1070F000B7421BD85046FDF7F7F929462046FFF75F +:10710000A3FFC8E7B742E4D9E68D10F802C0013208 +:10711000616B36B201F806C019B20133E1859BB24A +:10712000B4F932108B42A8BF0023CDE72B891E444F +:107130002E81D4F89430002BB0D02346024AC821C7 +:10714000484601F025FCA9E72174000838B583689A +:107150005C6940F20933994200F0EC8012DC40F2A5 +:107160000733994200F0A880B1F5427F00F0C68055 +:1071700040F2011399422ED0B1F5817F5AD06FF0C1 +:1071800018057DE06FF4506001440329F7D8032906 +:10719000F5D8DFE801F002051219A26600256FE0BC +:1071A000002A00F0E780D4F85E301360B4F8623053 +:1071B000938094F864309371F0E7002A00F0DA804D +:1071C00094F858301360E9E7204684F85920BDE868 +:1071D0003840FFF76BBC002A00F0CC80E3681360F6 +:1071E000236953606369D36094F8633003B3012B60 +:1071F0004FF480710CBF4FF4007300230B4394F8DD +:107200006210104602290CBF402100210B4343F0BD +:107210003003936094F85A10002914BF4FF00041D6 +:1072200000210B439360D4F85E10FDF7ADFBB5E78A +:107230001946E3E7002A00F09D801368E360536875 +:107240002361D3686361936894F85A20B2EBD37FCB +:10725000A4D0002B18DB94F859309A0712D443F0CD +:107260000303204684F85930FFF720FC054600232D +:107270002046A4F85A30FFF7F1FE012384F85D3070 +:10728000284638BD0025F2E70123A4F85A3094F8C7 +:107290005C307BB194F85930204623F0020343F070 +:1072A000010384F85930FFF701FC0123054684F8F7 +:1072B0005B30E2E70025E0E7EFF311800023802157 +:1072C000EFF3108372B681F3118883F31088218E57 +:1072D000E38D09B21BB2994208DCE38D218E1BB20B +:1072E00009B25B1AC1B281F311886BE7218EE58D7B +:1072F00009B2B4F932302DB2491BF2E7EFF3118035 +:1073000000238021EFF3108372B681F3118883F399 +:107310001088A18C638C09B21BB2994203DC638C88 +:10732000A18C1BB2DCE7A18C658C09B2B4F92630C4 +:107330002DB2E1E7EFF3118000238021EFF31083FA +:1073400072B681F3118883F31088618CA38C09B223 +:107350001BB2994206DAA38C618C1BB209B25B1A8C +:10736000013BBFE7618CA58C09B2B4F926302DB280 +:10737000491BF4E76FF0150582E710B5C06BEFF31A +:10738000118400238022EFF3108372B682F31188F8 +:1073900083F3108859B190F85D3013B9012380F858 +:1073A0005D30FFF75BFEE4B284F3118810BD80F816 +:1073B0005D10F8E738B5C46B94F8593094F85A105A +:1073C00003F0020584F85C20F1B17AB145B123F0F5 +:1073D0000203204643F0010384F85930FFF766FBAF +:1073E000012384F85B3094F85B0038BD84F85B209F +:1073F00035B943F00303204684F85930FFF756FBB4 +:107400002046FFF72BFEEEE7002DECD143F00303FF +:10741000204684F85930FFF749FB84F85B50E2E7D7 +:10742000FFF71CBE38B584680869EFF311850023A7 +:107430008022EFF3108372B682F3118883F31088F1 +:10744000B1F90A3013F16E0F0CD08BB9038104F13E +:107450009401FDF729F82046FFF700FEEDB285F311 +:10746000118838BD94F85630013B84F85630F5E762 +:1074700001462046FFF7E8FDF0E72DE9F74F044607 +:10748000EFF311834FF0800A01930023EFF3108391 +:1074900072B68AF3118883F31088D0F87080B8F838 +:1074A0000630602B38BF60230093D4F88C706FB324 +:1074B000D7F804B0DBF80000EFF31189EFF3108583 +:1074C00072B68AF3118885F310880021B4F822C0BF +:1074D0008EB2A28C0FFA8CFC12B2944502D0009BA3 +:1074E000B3421AD8618CA28C09B212B2914204D173 +:1074F000A26B00212046926A904716B12046FFF702 +:1075000073F85FFA89F989F31188C6B99DF80430D8 +:1075100083F3118803B0BDE8F08FA68CA26A36B25F +:10752000925D4254A28CB4F92660013212B29642A6 +:10753000A28402DC4FF00003A3840131C6E704F10A +:107540008C00FCF7D1FF94F8552059464046013A8B +:1075500084F855200122ABF80660CBF810708BF848 +:107560000420D8F800201269904700289DD0CDE76C +:1075700041B1C06B428C838C12B21BB29A4201D0D3 +:10758000FFF77BBF704770B50D4684680869EFF35D +:10759000118600238022EFF3108372B682F31188E4 +:1075A00083F3108804F18C01F6B2FCF77DFF94F8A8 +:1075B0005530013384F8553086F31188B5F90A3017 +:1075C00023B92046BDE87040FFF757BF70BD704734 +:1075D0002DE9F04F8FB0242207460E4605A8002162 +:1075E000F9F753FB4FF0020804234FF0030A4FF062 +:1075F000010943F25820CDF810800693CDE908A97F +:10760000CDE90A8AFCF7BCFD044638B96FF00B05DA +:1076100006B1346028460FB0BDE8F08F43F24C2B22 +:10762000002104F19C055A46F9F72FFB0DF1100CCF +:1076300084F85770BCE80F000FC5BCE80F000FC5F9 +:107640009CE80300C2231E4A85E8030084F85F30EB +:1076500008231021684684F864304FF4167384F8C8 +:1076600059A0638604F58A7384F86090636342F6D8 +:10767000E06384F80390E38404F55B73A362114B29 +:10768000C4E90E3404F5405383F85082C3F84C2209 +:10769000C3F854423B460C4A01F053FC214668466D +:1076A000FEF74AFF051E04DA20460024FCF760FDC1 +:1076B000AEE75C442046FCF74DFB0546A8E700BF5B +:1076C00024A700083CA7000814A7000830B585B01F +:1076D00085680B4A102195F857300446684601F03A +:1076E00030FC684600F0ABFE2046FCF74DFB05F190 +:1076F0007C00FAF7A9FC2846FCF73AFD05B030BD3E +:1077000014A7000870B50C4604282BD8DFE800F059 +:107710001C2803242600154D2846FDF71BF90023DD +:1077200022461946EE5C0133D1700232984216703F +:10773000F8DC00284FEA4003D8BF0223981C03233B +:10774000C0B26370207006E0032304204B7009234D +:1077500008708B70C87070BD054DDDE7054DDBE727 +:10776000054DD9E76FF01500F5E700BF7DA70008CC +:10777000F2A7000870A7000875A700080048704726 +:1077800092A70008012810B512D002281FD068BBAC +:10779000072305240B704C705269487162F07F0218 +:1077A0008A700322CA7040220A710A228A710CE090 +:1077B000072305240B704C70D26988718A700222ED +:1077C000CA7040220A7100224A71184610BD072370 +:1077D00005240B704C709269C87062F07F028A7049 +:1077E00040220A7100224A710122DFE70023ECE700 +:1077F0002DE9F0410D460446002800F08780002165 +:10780000042624274FF003080846FFF7F1FF8023E2 +:10781000012102224FF0090EA070E3710012FA2339 +:10782000A671E0704FF0100CA672052084F800E0FD +:10783000627022716171237284F809E06B6884F8C8 +:1078400015C04FF0060CE3720023A074E67584F8AF +:107850001AC04FF0070CE07684F81E802373617322 +:10786000A273E27321746374E7742375A17527769C +:107870006276277761776F6884F820C00F4484F8B8 +:107880002100E7776F6984F823804FF00A0867F0DA +:107890007F0784F8253084F8268084F822704027FA +:1078A00084F827E084F8247084F828606E6884F8EF +:1078B0002A300E4484F82B2084F82C8084F8296028 +:1078C00084F82D3084F82E3084F82F3084F830C0BE +:1078D00084F83100EE6984F8332084F8326084F84B +:1078E000347084F8353084F8361084F837C084F862 +:1078F0003800A86960F07F0084F8390084F83A20E5 +:1079000084F83B7084F83C3084F83D103E20BDE89C +:10791000F08110B514460846114601F0A7F920463B +:1079200010BD0846FBF78EB900F042B9F8B5837870 +:1079300004460E468B4223D2CB00FF2B22D889006F +:10794000406801F09FF9074668B1A5788020FCF7F0 +:107950001FFC47F8250070B9013DA3789D4205DA68 +:107960003846FCF705FC6FF016000AE057F82500D2 +:10797000FCF7FEFBF0E70135B542E7D36760A67080 +:107980000020F8BD6FF01700FBE701220021FCF793 +:10799000F4BDF8B504468578013D07D26068FCF770 +:1079A000E7FB2046BDE8F840FAF75BB9AF00702668 +:1079B0006368D8593044103E00F01EFA16F1100FDB +:1079C000F6D16368D859FCF7D3FBE5E72DE9F84F0A +:1079D000DDF828A0884617461D46064600F0D2FD71 +:1079E000814600F0A7FE041E3EDBBAF1000F5146AF +:1079F00099F80230B8BF0AF10701C9108B428B46D3 +:107A000009DC01314846FFF791FF041E03DA4846BE +:107A100000F0A6FE28E0DAF100030AF00704D9F826 +:107A200004C003F0070358BF5C425CF82B204FEA08 +:107A30008B0102EB041293682001D3B9C2F80080D5 +:107A400004EBCB04D9F80420535803445F60D9F801 +:107A500004305B5803449E60D9F804305B580344FB +:107A60004846DD6000F07CFE2046BDE8F88FD34636 +:107A7000DBE701341032082CDDD10BF1010A99F853 +:107A8000023000245345F2DC0BF102014846FFF7B7 +:107A90004DFF041EBBDBD9F804304FEACA0453F88B +:107AA0002A30C3F80080D9F8043053F82A305F60D8 +:107AB000D9F8043053F82A309E60D9F8043053F8CE +:107AC0002A30DD60A3E7F8B5002305460F460B60BA +:107AD00000F058FD0646F0B1002D1FDB8378B5EBB2 +:107AE000C30F1BDA00F026FE041E0FDB7368EA10DA +:107AF00005F0070553F8220000EB05153D60AB6863 +:107B000033B12B4630463B6000F02AFE2046F8BDDC +:107B10006FF00804F6E76FF00A04F7E76FF0080467 +:107B2000F4E7F0B585B0044600F02CFD054600F002 +:107B300001FE002814DB002C0DDBAB78B4EBC30F87 +:107B400009DAE2106B6804F0070453F8220000EB36 +:107B50000414A36833B9284600F002FE6FF0080051 +:107B600005B0F0BD23466E4604F1100718680833CF +:107B700053F8041C3246BB4203C21646F6D110220B +:107B800000212046F9F781F8284600F0E9FD684613 +:107B900000F032F9E4E710B5FFF7C3FF041E05DA81 +:107BA0006442FCF777FC04604FF0FF34204610BDC0 +:107BB00000F05AB838B50F4C00F0DCFE054663689B +:107BC000984204D1238900200133238138BD204607 +:107BD00000F0B8FD002807DAFCF75CFC0068042818 +:107BE000F5D08C28F3D040420028EFD10123656006 +:107BF0002381EBE78800002408B500F0BBFE0A48AB +:107C00000389012B0CD1002303814FF0FF33436024 +:107C100000F0E4FD002805DABDE80840FCF73ABCB6 +:107C2000013B038108BD00BF8800002410B5034656 +:107C30000446184613F8012B2AB9001B1C30FCF728 +:107C4000A7FA18B910BD2F2AF3D1F6E700F11803EF +:107C5000013C14F8012F12B900221A70F2E72F2A02 +:107C6000FAD003F8012BF4E708B50348FFF7DEFF6D +:107C7000024B186008BD00BF8CA30008E813002465 +:107C800000232DE9F04116461360027888B0002ADF +:107C900045D08DF81C30CDE9010301A8CDE90333AF +:107CA000CDE9053300F04CF8002835DA019FDDE915 +:107CB0000354384600F036F8037880463846D3B18E +:107CC000FFF7B4FF48B96FF00B04069808B1FCF752 +:107CD0004FFA204608B0BDE8F0813DB16B68C0E9BD +:107CE00000436860474604460025E2E7A368C0E910 +:107CF0000043A060F6E7FFF799FF0028E3D035B115 +:107D00006B68C0E90043686000243060DDE7A36869 +:107D1000C0E90043A060F7E76FF01004D5E76FF00B +:107D20001504D6E7017803460246013031B12F2908 +:107D3000F8D11346013219782F29FAD01846704726 +:107D4000F8B5036805461A782F2A08D0274A143058 +:107D5000274901F0E9F86B69002B41D02B60254BD6 +:107D600028681C6803782F2B3DD1002637464CB974 +:107D700022466FF001032A61C5E90004C5E90276D5 +:107D80001846F8BD04F11701431E11F801CF13F88E +:107D9000012FBCF1000F0FD10AB12F2A17D1FFF725 +:107DA000C1FF0378BBB1E38903F00F03032B14D0A9 +:107DB000A368264600240BE022B12F2A02D0944566 +:107DC00005D3E2D900246FF001032246D3E76368AC +:107DD00027461C46CBE70246CDE702460023CAE70A +:107DE0006FF00B03CCE76FF01503C9E78CA3000815 +:107DF000B8A70008E813002470B5866805467EB170 +:107E000034691CB164680CB1A0470446304600F0E8 +:107E100047FB0023C5E90033C5E90233204670BDA6 +:107E20003446FBE770B5866804460B4615463EB1FE +:107E300036692EB136691EB1B04700280DDA70BD23 +:107E4000012D05D0022D0AD025B16FF01500F6E7FF +:107E500062681344002BF8DB63606068EFE76FF043 +:107E60005700ECE71FB50C4603A90192FFF72BFE64 +:107E7000002804DB019A21460398FFF7D3FF04B0E2 +:107E800010BD10B5FFF7EEFF041E05DA6442FCF7E3 +:107E900001FB04604FF0FF34204610BDC38913F08E +:107EA0000F030FD003697BB1CA0701D59A6872B17D +:107EB00011F002000DD0DB68002B14BF00206FF022 +:107EC0000C007047184670476FF0050070476FF060 +:107ED0000C0070472DE9F047054688B09246984659 +:107EE00000295BD012F0060F4FF0000601A80191A7 +:107EF00014BF109B4FF4DB79069618BFD3F800909F +:107F00008DF81C60CDE90266CDE9046600F0B5FA93 +:107F1000041E19DB029F51463846FFF7BFFF041EBF +:107F20000DDB1AF4006FC5E900A6C5E9027610D092 +:107F30000599284600F0BAF90028044611DA002312 +:107F40003846AB6000F0ACFA069868B1FCF710F95F +:107F50000AE0FB8903F00F03032B10D13B691C6877 +:107F600034B90698A0B90024204608B0BDE8F087CF +:107F700029EA0803524605992846A047DCE7012B69 +:107F800009D13B691B68002BEBD028469847D3E703 +:107F9000FCF7EEF8E7E76FF00504D0E76FF01504A3 +:107FA000E2E770B5044686B00D46164600F06EFF57 +:107FB000214603462A4602A80096FFF78BFF041EBF +:107FC0000CDB002304980093059BDDE90212FFF708 +:107FD000FDFC041E02DA02A8FFF70EFF204606B0E1 +:107FE00070BD0EB417B505AA52F8041B0192FFF735 +:107FF000D8FF041E05DA6442FCF74CFA04604FF027 +:10800000FF34204603B0BDE8104003B0704710B401 +:1080100003688468DB0707D55CB123694BB19B68B3 +:108020003BB15DF8044B18476FF00C005DF8044B52 +:1080300070476FF00800F9E71FB50C4603A90192DD +:10804000FFF741FD002804DB019A21460398FFF762 +:10805000DEFF04B010BD10B5FFF7EEFF041E05DA19 +:108060006442FCF717FA04604FF0FF34204610BD5D +:1080700010B40468A40708D583685BB11B694BB1D1 +:10808000DB683BB15DF8044B18476FF00C005DF8FE +:10809000044B70476FF00800F9E71FB50C460192DA +:1080A00059B103A9FFF70FFD002804DB019A21460F +:1080B0000398FFF7DDFF04B010BD6FF01500FAE77D +:1080C00010B5FFF7EAFF041E05DA6442FCF7E2F997 +:1080D00004604FF0FF34204610BDB1F5417F08B574 +:1080E000C36805D159681046FCF710FC002008BD94 +:1080F0006FF01800FBE770B5C56806460C462868A7 +:10810000002956D0212A54D9C38903F00F03032B29 +:108110000BD103690A4629465B6B9847002844DB6C +:10812000736822200133736042E0A96800293ED0C1 +:1081300021221831601CFCF7F1FB00232370AB688F +:108140001A6932B1DB8903F00F03022B17D1062322 +:108150002370AB689A680AB91B690BB904232370B2 +:10816000FFF728FDAC686368AB6013B19A890132F0 +:108170009A81FFF741FD204600F092F9D0E7072BE6 +:1081800001D10923E4E7032B01D10423E0E7012B0C +:1081900001D10223DCE7042B01D10323D8E7052B0F +:1081A000D6D0062BD5D10723D2E7831C00D10020DF +:1081B00070BD6FF01500FBE770B5C468D4E90056D8 +:1081C000EB8903F00F03032B0ED12B691B6BA3B1BB +:1081D0002146284698470446284600F061F9304673 +:1081E000FBF7C6FF204670BDA06808B100F058F943 +:1081F00020460024FBF7BCFFEEE71C46ECE72DE928 +:10820000F04306468BB089461746002A48D1D0F87D +:108210000C804468D8F80050EB8903F00F03032B5F +:1082200020D1A1420CDA2B699B6B2BB96FF085042E +:1082300020460BB0BDE8F0833C46414628469847AF +:108240002746B94504DC3C46002CF1DB7460EFE7BF +:108250002B6901AA414628465B6B9847041EE7DB61 +:108260000137EEE7A142BABFAD681446D8F808500E +:10827000FFF7A0FC0DB1A1450FD1D8F80870C8F8E0 +:10828000085015B1AB890133AB81FFF7B5FC002F66 +:10829000DAD0384600F004F9D6E701346D68E9E732 +:1082A000012A0CBF44686FF01504C1E7F7B5856873 +:1082B00006460F46EB8903F00F03032B19D12B69F8 +:1082C00023B3DC6A14B35B6B03B301AA2846A0474F +:1082D000041E0BDB019B1D60019D384600F0B2FFC0 +:1082E00068600D48C6E9020500F0B7F8204603B003 +:1082F000F0BD0C20FBF74CFF034650B10190002469 +:108300000560A868986000F0A8F8E5E76FF05704EA +:10831000ECE76FF00B04E9E794000024C3685968A8 +:10832000FFF7C4BF2DE9F347061E89461446984659 +:108330005DDB12B900F0A6F90446022E18DD01A992 +:108340003046FFF7C0FB051E04DB019B986840B96F +:108350006FF00105B8F1000F3DD00023C8F80030E0 +:1083600039E04946FFF79AFD10B16FF00C05F1E7CF +:10837000022EA76836DD4C20FBF70AFF0446C8B37F +:1083800007F12C0A504600F0A5F9051E03DA204635 +:10839000FBF7EEFEDEE7D7F8183103B31C6050465A +:1083A000C7F8184100F0DCF92046FCF735FA04F173 +:1083B000240304F14402666063612362A4F84490DC +:1083C000C4E906230C2384F84630B8F1000F14D01A +:1083D0000025C8F80040284602B0BDE8F087C7F87D +:1083E0001441DCE74C2404FB06743034DFE76FF003 +:1083F0000805AFE76FF00B05ACE74546EBE7F0B5D6 +:1084000085B007460E461D460192FFF7D3FB041EBA +:1084100012DB03AA01993846FFF732FC041E09DB80 +:10842000039B0024DA8922F00F0242F00102C3E923 +:108430000465DA81FFF7E0FB204605B0F0BD38B5F2 +:108440000546FFF7B7FB041E05DB284600F06BF876 +:108450000446FFF7D1FB204638BD38B5044650B17D +:10846000FFF7A8FB051E04DBA3890133A381FFF7F7 +:10847000C3FB284638BD0546FBE738B50546FFF780 +:1084800099FB041E0ADB2846FFF75AFC041EA1BF15 +:108490006A68938901339381FFF7AEFB204638BDAC +:1084A00010B50446C8B1FFF785FB0028FBDBB4F923 +:1084B0000C304BB9E389DB060BD5FFF79DFB20465B +:1084C000BDE8104000F044B8013B1BB2002BA38173 +:1084D000F0DDBDE81040FFF78FBB10BD10B50446BE +:1084E00088B0D0B100240123019001A806948DF832 +:1084F0001C30CDE90244CDE90444FFF721FCA04241 +:1085000007DBDDE90242636852B153600023C4E92E +:108510000033069808B1FBF72BFE204608B010BDCB +:10852000049A9360F2E710B5FFF7D8FF68B1B0F98D +:108530000C4034B1C28942F01002C2816FF00F00CA +:1085400010BD00F005F82046FAE76FF00100F7E7EC +:1085500010B5044650B14068FFF7FAFFA068FFF776 +:10856000F7FF2046BDE81040FBF702BE10BD00F04B +:1085700067BBFFEC024A136801331360704700BF0A +:10858000EC130024024B1B68986800B1243070473C +:10859000C40300240F4B10B51B680446B3F9202018 +:1085A000002A0ADD1A7C037C9A4206D20A49F9F7AE +:1085B000A1FD01230020237710BD06492046F9F7CD +:1085C00099FD022320B10322227722681377F3E773 +:1085D0002377F1E7C4030024B803002438B54368C7 +:1085E00004465BB90368032201251A772046044933 +:1085F000FBF7AAFF00232846237738BD0025F5E7BF +:10860000C4030024F0B5134D0020134C02262A6841 +:10861000032723681BB923606360F0BD1268B2B101 +:1086200093F810C0117C8C45F8D95168D3F800C07C +:10863000C3E9002139B90120536016772B601F77F9 +:108640001A466346E6E70B6053601E77F8E7536807 +:10865000FFDE00BFC4030024B8030024024B1B68E4 +:1086600098682C30704700BFC4030024044B1B687B +:1086700023B11868B0FA80F04009704701207047B4 +:10868000C4030024014B1868704700BFC4030024D2 +:1086900038B50F4B0C461D6870B1F9F789FAA0B1D7 +:1086A000EB8B03F00303022B07D0AA6883689A427E +:1086B00003D06FF00C0007E02846436B2360836B08 +:1086C0006360C36B0020A36038BD6FF00100FBE75F +:1086D000C403002438B5164B1C68EFF31185002342 +:1086E0008022EFF3108372B682F3118883F310882F +:1086F000D8B103881BB2002B038803F1FF331BB2F0 +:10870000038005DD00202064EDB285F3118838BDBB +:1087100000232064052120466384F9F789FEB4F91B +:1087200022000028F0D04042EEE76FF01500EBE7A2 +:10873000C403002410B504462046FFF7CBFF031DF9 +:10874000FAD010BD10B5FFF7C5FF041E06DA64426B +:10875000FBF7A0FE04604FF0FF3010BD0020FCE7E7 +:1087600038B5002834D0EFF3118500238022EFF3D1 +:10877000108372B682F3118883F31088038847F65A +:10878000FF721BB2934205D1EDB285F311886FF0F1 +:108790008A0038BD038801331BB2038003881BB2F3 +:1087A000002B0EDC0C4B1C685CB1236C83420DD19A +:1087B00004F12400F9F748FC002320462364F9F76C +:1087C0000DFFEDB285F311880020E2E72468EBE7A6 +:1087D0006FF01500DDE700BFD803002410B5FFF7E8 +:1087E000BFFF041E05DA6442FBF754FE04604FF03D +:1087F000FF34204610BD70B505460C46F8F7B2FBB5 +:10880000EFF3118600238022EFF3108372B682F318 +:10881000118883F310882B881A0409D42B881B0431 +:108820000ED5F6B286F31188F8F7ACFB002070BDC8 +:10883000002CF3DD013C2846FFF792FF24B2EAE763 +:108840002C80EEE737B5041E0D4616DB1F2917D81E +:10885000F8F788FB00230422204669468DF8005073 +:108860008DF801308DF802200193F9F72BF80446BA +:10887000F8F788FB204603B030BD6FF05704F9E7E6 +:108880006FF01504F6E7FFEC07B568B1084A002160 +:10889000B0FBF2F302FB130000934FF47A735843DA +:1088A0000190684600F0EEF803B05DF804FB00BFED +:1088B00040420F0038B50F4C25682846FFF78EFE62 +:1088C0000D4B1B680BB1FFF79DFE24682846042161 +:1088D000238C0133238402232377F9F7E9FB012159 +:1088E000E86800F019F803232377238C013B2384E5 +:1088F00038BD00BFC4030024B8030024054B18682A +:1089000030B1037F032B01D1C06870476FF00200C4 +:10891000704700BFC403002470B50E46EFF3118505 +:1089200000238022EFF3108372B682F3118883F361 +:108930001088F9F73DF90446EDB2A0B1027F0C4B67 +:1089400053F83210FBF700FE85F311880021204612 +:108950003246F9F7D1F8E18B204601F00301BDE87A +:108960007040F8F785BD85F311886FF0020070BD87 +:108970002CA20008054B186830B1037F032B01D1EE +:10898000C06870476FF00200704700BFC403002446 +:108990002DE9F0410C46164698460546002839D088 +:1089A000002A37D0002935DBEFF31187002380221E +:1089B000EFF3108372B682F3118883F31088436853 +:1089C0000BB1F9F741FB1F4901346E600E68C5F821 +:1089D0000C801EB92846FBF767FD2CE03046334675 +:1089E00000229968521801D5196831B9A24214DCE5 +:1089F000196829B9A41A1349ECE718460B46F0E7A1 +:108A00008868024418460B46F0E70E4A294600F0F3 +:108A100048FA10E06FF0150012E099689E42A2EB50 +:108A20000102A4EB0204A1EB04019960EDD1054918 +:108A3000284600F030FAAC60FFB287F311880020BE +:108A4000BDE8F0814009002438B50D4C236843B1DE +:108A50009A680025013A9A60236813B19B68002B3D +:108A600000DD38BD2046FBF73FFD23681BB19A6847 +:108A700081680A449A6043684560C0689847EBE79C +:108A8000400900242DE9F7430F46054600283BD056 +:108A900042681F4B9A4237D8EFF311860023802299 +:108AA000EFF3108372B682F3118883F31088DFF836 +:108AB00064906846F6B2D9F80080FBF7AAFD2A4612 +:108AC0000021684600F038F810F10B0F044606D17B +:108AD00086F311880024204603B0BDE8F08387B1F7 +:108AE00001A9284600F0FAF9D9F800300198394672 +:108AF000A3EB080290428ABFC01A0020404400F055 +:108B0000DFF986F31188E6E76FF01504E3E700BFAD +:108B1000FFC99A3BEC130024027F062A0AD140F2D7 +:108B2000FF22A0F85C20742280F85E2000220266FA +:108B3000F9F754BD7047FFEC394B2DE9F347074671 +:108B40000D4692461C68EFF3118800238022EFF354 +:108B5000108372B682F3118883F31088066820466A +:108B6000F9F7EAF930405FFA88F80190A0B101A85E +:108B7000F8F76AFD01462046F8F714FD1DB1436879 +:108B80002B6083686B600679F8F730FD88F31188F5 +:108B9000304602B0BDE8F0873B68A364BAF1000F2D +:108BA00033D0DAF8043004F124091E4ED917DAF86C +:108BB00000C09E191C481D4A4FF0000341F10001FE +:108BC000ECFB0061304600F0C7FC23460146184A22 +:108BD0004846FFF7DDFE20460621F9F729FC484606 +:108BE000F9F732FA94F85C1000231F29A36411D816 +:108BF0003846FBF712FD80B194F85C60002DC5D0BB +:108C0000E36D2B60236E6B60C0E706212046F9F709 +:108C10000FFCE7E76FF00A06F0E76FF00306EDE7F9 +:108C2000C40300243F420F0000CA9A3B40420F0099 +:108C3000198B000808B500F021FC002008BDFFECEE +:108C400010B5084B4FF0E0240022074963610F2064 +:108C5000A261F8F72FF907230F202361BDE8104028 +:108C6000F7F7A6BEFF520700358C000838B504465A +:108C70004518207808B1AC4200D138BD0134F9F76D +:108C8000E1FFF6E7024B0A460146186800F002B819 +:108C9000B80E00242DE9F84F804614460E4621B93F +:108CA0001146BDE8F84FFBF78BBB12B9FBF72CFB65 +:108CB00018E002F1170323F00F0B5A4500F2B280BF +:108CC000A1F10805FBF7CCFA56F8089CCB450CD867 +:108CD00004D25A462946404600F0A6F8344640469B +:108CE000FBF7E2FA2046BDE8F88F56F8041C05EBC6 +:108CF000090A21F00101DAF80430691ADA07486834 +:108D00004CBF002755F80970C30707EB090354BF90 +:108D10000868002003445B4571D3B842ABEB0903FC +:108D200008D2984252D2A3EB000B034633B95B46FC +:108D3000344623E09F42FBD2DB1BBB46D1E9024213 +:108D400094600CB1CA68E2609842A5EB030540D973 +:108D50000A68D21A4B440A602B600C6844F0010484 +:108D60006C60DAF8040000F001001843CAF804004F +:108D70004046FBF7A1FA05F108045B46D3B10AEBC4 +:108D80000700DAE90212916011B1DAF80C20CA602A +:108D90002A689F421A442A602BD9FB1AA918AB50A3 +:108DA0002A684A60476807F001073B434360404632 +:108DB000FBF782FA4046FBF777FAB44292D0A9F16A +:108DC000080231462046F7F74BFE8BE74FF0000BC9 +:108DD000ACE72B6809EB03026B6843F001032A60E0 +:108DE0006B60DAF8043003F001031343CAF804306F +:108DF000C1E7436803F001031A434260DAE74046E3 +:108E0000FBF752FA21464046FBF7DAFA04460028FF +:108E10003FF468AF3146A9F10802F7F721FE314669 +:108E2000404643E700245DE7F0B40C680B46064675 +:108E30000D196968C90719D41859D5E902172844CA +:108E4000B96009B1ED68CD601D6899181C59AD1A5B +:108E500025449D504A601A6044689B5804F0010400 +:108E60001C4344603046F0BCFBF726BA02F1100107 +:108E70008C4209D39918A41A9C504A601A609B58D6 +:108E800043F001036B60EEE7F0BC704708B500F0FB +:108E900039FA406B08BD0B68036003B9486008608D +:108EA0007047034608461146126812B14A689A4252 +:108EB00001D1FBF7F9BA1A68026018607047FFEC3D +:108EC0004FF47A7290FBF2F302FB13000B60024B3B +:108ED000584348600020704740420F0038B543684F +:108EE0000C460568084AD917E5FB02311846074BBE +:108EF000074AC0184FF0000341F1000100F0DCFA0E +:108F00002060002038BD00BF00CA9A3B3F420F00DE +:108F100040420F00084631B10139022934BF6FF0D9 +:108F200085006FF0150070470EB403B503AA52F820 +:108F3000041B019200F01DF802B05DF804EB03B0D1 +:108F400070470CB40A4600B589B071B1014602A859 +:108F500000F022F90BAA0A9902A80192FBF764FD1E +:108F600009B05DF804EB02B0704702A800F02CF9DC +:108F7000F0E770B58EB014460D46064604A803927D +:108F800000F022F92246294604A8FBF74DFD079A76 +:108F9000013210460192FBF7F3F8044660B1014636 +:108FA000019A08A800F0F8F8039A294608A8FBF7E8 +:108FB0003BFD34600EB070BD4FF0FF30FAE70A227F +:108FC000002100F000B837B50C460190009290B334 +:108FD00001A800F02BF9019B009A1D782D2D01D0DE +:108FE0002B2D12D1013301932146019800F025F871 +:108FF0002D2D0FD1B0F1004F09D9FBF74BFA2223E9 +:1090000003604FF000407CB915E00025ECE7FAD092 +:109010004042F8E7002805DAFBF73CFA2223036018 +:109020006FF000403CB135B1236813F8012CAA421F +:1090300001D1013B236003B030BD2DE9F04385B081 +:109040000E4614460190002850D001A800F0EEF81A +:10905000019B1F782D2F01D02B2F18D101330193A5 +:1090600001A9204600F046F8051E12DAFBF712FAB5 +:109070000024162303606EB337B1019B13F8012C53 +:10908000BA4201D1013B0193019B336022E00027EA +:10909000E6E74FF0FF380024B8FBF5F805FB08F9C8 +:1090A0006FEA0909019B03AA2946187800F098F88D +:1090B00058B1444503D8039B10D199450EDAFBF70C +:1090C000E9F94FF0FF34222303602D2FD3D16442FE +:1090D000002ED2D1204605B0BDE8F08304FB053454 +:1090E000019B01330193DDE70446CDE70029FBD165 +:1090F0000C46EFE770B50D460C6890B92378302B1D +:1091000021D16378661C03F0DF03582B1DD1024682 +:109110001021A07800F064F8B8B1023410202C605F +:1091200070BD102809D12378302BF8D1637803F073 +:10913000DF03582BF3D10234F1E7831E182BEED94D +:109140004FF0FF30ECE70A20E9E734460820E6E775 +:1091500038B50546C0686B691B1A934228BF134691 +:10916000002B1C460ADD2B6922461844F7F778FCD1 +:10917000EB682A6900212344EB60D154204638BDB6 +:1091800007B501228DF807100DF10701FFF7E0FF89 +:1091900003B05DF804FBFFEC064B013A0360064B9D +:1091A00042614360054B83600023C0E903310B70CB +:1091B000704700BF81910008519100086B5400086E +:1091C000C3680133C3607047034B0360034B836084 +:1091D0000023C360704700BFC19100086B540008B2 +:1091E0000A290ADC2F281EDD2F3181421BDBA0F16A +:1091F0003003012002B113607047242913DCA0F171 +:109200003003092BF3D9602805DD563181420ADB92 +:10921000A0F15703EDE7402805DD3631814202DB3E +:10922000A0F13703E5E700231846E3E770B50446ED +:1092300005682E460135307800F069F80028F8D12D +:10924000266070BD13B50190FBF784FB0130FAF77F +:1092500097FF044610B10199FBF758FB204602B076 +:1092600010BDFFEC014A00F003B800BFF01300246A +:109270002DE9F04188461646044610B9CAB1146873 +:10928000BCB125462C4615F8011BA9B1404600F09B +:1092900015F80028F6D129782F46013539B1404616 +:1092A00000F00CF80028F6D000233B702F4606B1E2 +:1092B00037602046BDE8F0810C46FAE703461A788D +:1092C000184601338A4202D0002AF8D1104670476E +:1092D0000A4640F2011100F08FB870B504461646F8 +:1092E0000D4639B100F022F8022D03D100212046AD +:1092F00000F017F8324620464FF48171BDE8704007 +:1093000000F07AB808B5FBF761FB006808BD2028BB +:1093100005D0093804288CBF0020012070470120A7 +:1093200070470A464FF48A7100F066B8002240F296 +:10933000151100F061B8F0B5876885B004460D4698 +:109340001668002F55D03B69C3B940F20D339D42DA +:109350000DDCB5F5417F0EDBA5F54175092D0AD869 +:10936000DFE805F02A09090909090916222640F251 +:109370000F539D422CD06FF0180007E05B69002B63 +:10938000E3D03246984710F1190FDED005B0F0BD9A +:10939000236836B1326822B143F0400300202360D5 +:1093A000F4E723F04003F9E7236843F48063F5E72B +:1093B000236823F48063F1E7FB8903F00F03032B99 +:1093C000D9D03146384605B0BDE8F04000F032B89B +:1093D0003B69002BCFD05B69002BCCD001AA40F2B7 +:1093E0000C51204698470028D0DBBDF90C30338063 +:1093F000CCE76FF00800C9E70EB477B507AD01A957 +:1094000055F8046B0095FEF75EFB041E06DB2A464A +:1094100031460198FFF78FFF041E05DA6442FBF71F +:1094200039F804604FF0FF34204603B0BDE87040C7 +:1094300003B0704738B504460D46C9B110B908707D +:10944000002038BD0068FFF7F5FF0028F9DB04F1C4 +:109450001801284600F020F8A06820B9E28902F03F +:109460000F02032AEDD10449284600F015F8E7E77A +:109470006FF01500E5E700BFE0A7000808B5054B51 +:109480000BB1FFF777F8FFF7DFFABDE80840F7F711 +:109490004CBC00BF7585000838B505460C46FBF787 +:1094A00059FA611E2B1811F8012F12B928461A70AB +:1094B00038BD03F8012BF6E77BB972B90029BEBFAE +:1094C00000204FF0004106E008BF00281CBF6FF0ED +:1094D00000414FF0FF3000F0DFB9ADF1080C6DE94D +:1094E00004CE002909DB002B1ADB00F06DF8DDF853 +:1094F00004E0DDE9022304B07047404261EB410122 +:10950000002B1BDB00F060F8DDF804E0DDE902234E +:1095100004B0404261EB4101524263EB43037047A8 +:10952000524263EB430300F04FF8DDF804E0DDE95D +:10953000022304B0404261EB41017047524263EBA9 +:10954000430300F041F8DDF804E0DDE9022304B054 +:10955000524263EB4303704753B94AB9002908BF2D +:1095600000281CBF4FF0FF314FF0FF3000F094B9DE +:10957000ADF1080C6DE904CE00F026F8DDF804E04A +:10958000DDE9022304B070479FED0B6B41EC170B34 +:109590009FED0B5B27EE066BBCEEC66BB8EE464B41 +:1095A000A4EE457BFCEEC77B16EE101A17EE900A70 +:1095B000704700BFAFF30080000000000000F03DE6 +:1095C000000000000000F0412DE9F047089D04462E +:1095D0008E46002B4DD18A42944669D9B2FA82F266 +:1095E00052B101FA02F3C2F1200120FA01F10CFAA2 +:1095F00002FC41EA030E94404FEA1C48210CBEFBDA +:10960000F8F61FFA8CF708FB16E341EA034306FB62 +:1096100007F199420AD91CEB030306F1FF3080F0F1 +:109620001F81994240F21C81023E63445B1AA4B23E +:10963000B3FBF8F008FB103344EA034400FB07F7E0 +:10964000A7420AD91CEB040400F1FF3380F00A8121 +:10965000A74240F207816444023840EA0640E41B16 +:1096600000261DB1D4400023C5E900433146BDE8C2 +:10967000F0878B4209D9002D00F0EF800026C5E964 +:10968000000130463146BDE8F087B3FA83F6002E7C +:109690004AD18B4202D3824200F2F980841A61EBF4 +:1096A000030301209E46002DE0D0C5E9004EDDE712 +:1096B00002B9FFDEB2FA82F2002A40F09280A1EBFA +:1096C0000C014FEA1C471FFA8CFE0126200CB1FB4F +:1096D000F7F307FB131140EA01410EFB03F0884248 +:1096E00008D91CEB010103F1FF3802D2884200F2D5 +:1096F000CB804346091AA4B2B1FBF7F007FB101167 +:1097000044EA01440EFB00FEA64508D91CEB040404 +:1097100000F1FF3102D2A64500F2BB800846A4EB5F +:109720000E0440EA03409CE7C6F12007B34022FA4A +:1097300007FC4CEA030C20FA07F401FA06F31C4379 +:10974000F9404FEA1C4900FA06F3B1FBF9F8200C86 +:109750001FFA8CFE09FB181140EA014108FB0EF0CC +:10976000884202FA06F20BD91CEB010108F1FF3A1C +:1097700080F08880884240F28580A8F10208614428 +:10978000091AA4B2B1FBF9F009FB101144EA014136 +:1097900000FB0EFE8E4508D91CEB010100F1FF34E1 +:1097A0006CD28E456AD90238614440EA0840A0FB79 +:1097B0000294A1EB0E01A142C846A64656D353D04F +:1097C0005DB1B3EB080261EB0E0101FA07F722FA73 +:1097D00006F3F1401F43C5E9007100263146BDE89C +:1097E000F087C2F12003D8400CFA02FC21FA03F3FF +:1097F000914001434FEA1C471FFA8CFEB3FBF7F080 +:1098000007FB10360B0C43EA064300FB0EF69E42A4 +:1098100004FA02F408D91CEB030300F1FF382FD23D +:109820009E422DD9023863449B1B89B2B3FBF7F6E5 +:1098300007FB163341EA034106FB0EF38B4208D9BE +:109840001CEB010106F1FF3816D28B4214D9023EFF +:109850006144C91A46EA004638E72E46284605E71D +:109860000646E3E61846F8E64B45A9D2B9EB0208EE +:1098700064EB0C0E0138A3E74646EAE7204694E77E +:109880004046D1E7D0467BE7023B614432E73046B1 +:1098900009E76444023842E7704700BF0720704779 +:1098A00010B50920094CF8F79DFC4FF000632F20FC +:1098B000C4F88034F8F796FC2E20F8F793FC0023C8 +:1098C000C4F88034C4F8D83410BD00BF004002583A +:1098D00008B5042000F0B6F9064B4FF47A70DB6847 +:1098E000584300F0A3F900F0D3F9BDE8084000F0B8 +:1098F000B9B900BFB000002408B500F0D1F900F0FC +:10990000B9F9002000F09EF90020BDE8084000F001 +:109910008DB9FFEC0F4BD3F8002442F00102C3F8DD +:109920000024D3F800245207FBD50022C3F81024EA +:10993000D3F8002422F0A85222F41022C3F8002405 +:10994000054AC3F82C24D3F8002422F48022C3F85B +:1099500000247047004002580000FF0108B54FF096 +:10996000006000F036FA4FF00160BDE8084000F0FA +:1099700030BA08B500F0BEFB4FF0006000F016FAF8 +:109980004FF00160BDE8084000F010BA00F0CEBA18 +:109990004FF0E023C3F8080D70470E2894BF4FF432 +:1099A000003000207047431E0D2B10B5044609D827 +:1099B00021B12046BDE8104000F047BA00F030FA6F +:1099C0000028F6D110BD00F1006000F5003000F075 +:1099D000ADBB830705D100F1006000F5003000F059 +:1099E000E5BB0020704700207047FFEC014B186872 +:1099F000704700BF0010005C234BF0B51A680446A6 +:109A0000224BC2F30B06120C1F885868BE421D7A07 +:109A10002BD09F89BE4205D101200C2505FB0033C8 +:109A200058681D7A41F203039A4220D042F20103A2 +:109A30009A421ED042F203039A421CD041F2010323 +:109A40009A4208BF5A25621E0B46441E0A4493429E +:109A500017D214F8016F581C7EB92C2482421C7056 +:109A600001D9981C5D70401AF0BD0020D5E759253A +:109A7000E9E75825E7E75625E5E7034600F8016CD6 +:109A8000E5E71846EFE700BF0010005CC0000024C7 +:109A900000F1FF5000F58F10D0F800087047FFEC80 +:109AA000012802D0022804D0704700210248F8F7AC +:109AB00083BB00210148FAE72F0904002E090400A6 +:109AC0000128014602D0022803D070470248F8F767 +:109AD00073BB01210148FAE72F0904002E09040095 +:109AE000012808B502D002280BD008BD0948F8F7B4 +:109AF0005FFC80F00100C1B20648BDE80840F8F7FD +:109B00005BBB0548F8F754FC80F00100C1B2024885 +:109B1000F3E700BF2F0904002E090400D0E900324A +:109B200083F308881047FEE74FF0E0224FF400303F +:109B300070B5D2F8883D0024314D43F47003C2F86B +:109B4000883D1C222F4B1C725C729A72DC72F8F7F3 +:109B500049FB2D48F8F746FB2C48F8F743FB01205A +:109B6000F6F7B4FD20462E6DF6F7B0FD284B9E4269 +:109B700041D101202646F6F7A9FD20462C65F6F7CF +:109B8000A5FD244800F012FB0546234800F00EFB1B +:109B9000224B98420ED125F0FF02214B9A4209D167 +:109BA000EDB21E2D06D84FF47A7000264543AC4224 +:109BB00038BF2C460920F8F7FBFB054660B95EB1BB +:109BC000FBF7AEFD0120F6F781FD0D4B104A2C4648 +:109BD00028461A65F6F77AFD01211248FBF723FDA6 +:109BE00002211148FBF71FFD20460024FBF7E8FD8A +:109BF000FBF796FDF8E741F288340126C1E700BF84 +:109C000000400058B00000242F0904002E09040071 +:109C100007B007B0A0010208A40102085D7D05C5D8 +:109C200000ECC292E2A70008F4A70008044B1B68EE +:109C300058434FF0E02320F07F405861704700BF49 +:109C4000D8000024021E054B05480CBF0821012145 +:109C500002F0040219600421F6F756BDD800002472 +:109C600010E000E0012200210148F6F74DBD00BFE1 +:109C700010E000E000220121044808B5F6F744FD99 +:109C80004FF0E02300229A6108BD00BF10E000E021 +:109C9000022200210148F6F737BD00BF10E000E0C6 +:109CA000002202210148F6F72FBD00BF10E000E0BE +:109CB000042838B505460C4613D80120F6F7C6FC33 +:109CC000032D094B4FF000000CBF24F0FF010021D1 +:109CD00053F825301943054B1965F6F7B7FC0020FA +:109CE00038BD4FF0FF30FBE71CA8000800400058CB +:109CF0000128044608B502D10021FFF7D9FF20460C +:109D0000F7F70AF800F0E2F9436803F110010A6876 +:109D1000D207FCD4DA68D20705D5034A5A6002F1AB +:109D2000883243685A6070472301674502460A48F3 +:109D30008168914203D801F5801191420AD8074801 +:109D40008168914205D801F58011914298BF0020A9 +:109D500070470020704700BFDC000024F0000024A2 +:109D600020B40D46406811461A4628445DF8045B4D +:109D7000F6F7CABC012300220C21FFF7F1BFFFEC6C +:109D800038B50546BFF34F8F074C6B681B6913F05E +:109D9000070307D00120F6F7CDFC013CF5D16FF0A9 +:109DA0000F0038BD1846FCE7404B4C0038B5FFF7B4 +:109DB000BDFF054650B1FEF7BDFC041E04DB28467E +:109DC000FFF7A2FFFEF7CCFC204638BD6FF012046F +:109DD000FAE738B5FFF7AAFF054658B1FEF7AAFC27 +:109DE000041E05DB2846FFF7C5FF2846FEF7B8FC32 +:109DF000204638BD6FF01204FAE7B0F5803F08B591 +:109E000003460AD200F580004001FFF78FFF026988 +:109E100080689B1A00EB431008BD4FF0FF30FBE752 +:109E2000B0F5803F08B50DD2FFF7E7FF002300F142 +:109E3000200201780130FF2918BF01338242F8D196 +:109E4000184608BD6FF00D00FBE7F8B5044600F5B5 +:109E500080600F2C4FEA404562D82846FFF766FF26 +:109E60000646FEF767FC00284DDB3046FFF788FF0B +:109E7000074600284BD13046FFF746FF04233A46F9 +:109E80000C21FFF76DFFF3684FF470620C21E31AA9 +:109E900030461B0203F4E063FFF762FF80233A467B +:109EA0000C213046FFF75CFF3046FFF769FF0446A0 +:109EB00050BB034604220C213046FFF751FF2346D6 +:109EC0004FF470620C213046FFF74AFF3046FFF72F +:109ED00051FF3046FEF744FC2CBB2846FFF726FF17 +:109EE00008B305F5FF3000F2FF10FFF71FFFD0B1F8 +:109EF000284605F5003383420CD1002C14BF6FF0C7 +:109F000004004FF40030F8BD6FF00404DEE76FF09A +:109F10000404DEE702680430013218BF0134EAE7C6 +:109F20006FF00D00EFE76FF00400ECE72DE9F84F5C +:109F300006460F461546FFF7F9FE0446002800F0D6 +:109F4000C2808368B34200F2BE80AA1903F5801371 +:109F50009A4200F2B880FEF7EDFB002865DB204650 +:109F6000FFF70EFF8046002840F0AA8020462037E9 +:109F7000FFF7CAFE302325F01F0B0C211A46B94605 +:109F8000FFF7EEFEB3444246B04602230C212046C2 +:109F9000FFF7E6FED84532D0BFF34F8FBFF36F8F88 +:109FA00059F8203CC8F8003059F81C3CC8F8043077 +:109FB00059F8183CC8F8083059F8143CC8F80C3067 +:109FC00059F8103CC8F8103059F80C3CC8F8143057 +:109FD00059F8083CC8F8183059F8043CC8F81C3047 +:109FE000BFF34F8FBFF36F8F2046FFF7C9FE08BB4B +:109FF000636809F120091B6913F0C06F17D00023B3 +:10A0000002220C212046FFF7ABFE4FF0FF33002267 +:10A0100014212046FFF7A4FE2046FFF7ABFE002DDB +:10A0200041D12046FEF79CFB2846BDE8F88F08F199 +:10A030002008AFE76FF00405EEE74FF0FF33002292 +:10A0400014212046FFF78CFE326857F8203C9A42D4 +:10A0500033D1726857F81C3C9A422ED1B26857F837 +:10A06000183C9A4229D1F26857F8143C9A4224D1FC +:10A07000326957F8103C9A421FD1726957F80C3C6C +:10A080009A421AD1B26957F8083C9A4215D1F2693E +:10A0900057F8043C9A4210D1636820371B6913F0CB +:10A0A000C06F0AD120365E45C7D14FF0FF33002282 +:10A0B00014212046FFF754FEB3E76FF00405F4E7E0 +:10A0C0006FF00405ADE76FF00D00AEE74FF0E02153 +:10A0D000054BD1F80C2D02F4E0621343C1F80C3D9E +:10A0E000BFF34F8FFEE700BF0400FA052822FF21CF +:10A0F000F6F7CBBD10B5054C2046FFF7F7FF04F18E +:10A100002800FFF7F3FF024B636010BDF413002437 +:10A110000000020800F10801202208B54068FFF79E +:10A1200035FC202808BF002008BDFFEC1D4A20F0A8 +:10A130001F0310B554689C4225D0D46AA34224D191 +:10A140000123282404FB0323C0F3820413B93CBB7E +:10A15000154BD062A01C934243F820101FD1F4B9D4 +:10A160001A68072A1BD19A6A013210D003F1280419 +:10A170002046FFF7CFFF50B120464FF0FF34FFF7E6 +:10A18000B5FF204610BD0023DBE70023DCE70548D0 +:10A19000FFF7C0FF04460348FFF7A8FFF1E71C6084 +:10A1A0000024EEE7F41300241C140024144A38B5EC +:10A1B00020F01F035168056899421AD0D16A8B427A +:10A1C00015D101232824C0F382000A2104FB0324B3 +:10A1D00001FB0303944203F1020352F8235006D01B +:10A1E000072804D12046FFF795FF20B1ED4328460C +:10A1F00038BD0023E6E72046FFF778FFF7E700BF0A +:10A20000F41300243217002461726D76372D6D2F00 +:10A2100061726D5F686172646661756C742E630053 +:10A2200049646C65205461736B00FFEC0000000012 +:10A2300000000000B803002401000000C403002453 +:10A2400005000000C403002405000000A40300244E +:10A2500000000000D803002401000000E0030024F7 +:10A2600000000000D003002400000000626F6F7443 +:10A270006C6F616465725F6D61696E004170704200 +:10A2800072696E675570006972712F6972715F75BE +:10A290006E65787065637465646973722E63003CE3 +:10A2A0006E6F6E616D653E0001000000E5190008EB +:10A2B00002000000E519000803000000E51900088D +:10A2C00006010000C919000807000000C9190008AC +:10A2D00008010000C51900080A000000E51900087F +:10A2E00009010000E51900080B000000E51900084D +:10A2F0000C000000E51900080D000000E519000839 +:10A30000736572636F6E3A3A204552524F523A204B +:10A31000416C726561647920636F6E6E656374650C +:10A32000640A00736572636F6E3A205265676973E1 +:10A33000746572696E67204344432F41434D207317 +:10A34000657269616C206472697665720A00736572 +:10A3500072636F6E3A204552524F523A20466169FD +:10A360006C656420746F2063726561746520746825 +:10A3700065204344432F41434D2073657269616CEE +:10A38000206465766963653A2025640A0073657206 +:10A39000636F6E3A205375636365737366756C6C97 +:10A3A0007920726567697374657265642074686585 +:10A3B000204344432F41434D2073657269616C20F3 +:10A3C0006472697665720A0000000258000402583F +:10A3D00000080258000C025800100258000000004B +:10A3E00000000000001C02582F6465762F747479F9 +:10A3F000537800FF0000002400000000000000006F +:10A40000000000000000000000000000000000004C +:10A4100000000000092B00089D2B00087D2A000881 +:10A42000612A0008A1290008F52800080F29000862 +:10A4300049290008E72A0008552900085D29000875 +:10A440009529000895290008D52D0008452E0008FB +:10A450007D2E0008F52E00088D2E0008992E00088C +:10A4600000000000852D0008D9300008DB2E000810 +:10A47000D52E000885330008AF3000085D35000890 +:10A48000556D656D00FFECC200000000000000008B +:10A4900032000000010000004B000000020000003C +:10A4A0006E000000030000008600000004000000B1 +:10A4B0009600000005000000C80000000600000033 +:10A4C0002C010000070000005802000008000000F6 +:10A4D000B004000009000000080700000A000000A6 +:10A4E000600900000B000000C01200000C0000001A +:10A4F000802500000D000000004B00000E00000051 +:10A50000009600000F00000000E1000001100000B4 +:10A5100000C20100021000000084030003100000CC +:10A52000000807000410000020A10700051000002B +:10A5300000CA08000610000000100E0007100000FE +:10A5400040420F00081000000094110009100000A4 +:10A5500060E316000A10000080841E000B1000004B +:10A56000A02526000C100000C0C62D000D10000014 +:10A57000E06735000E10000000093D000F100000DC +:10A58000696E66006E616E00286E756C6C2900FF46 +:10A590000080E03779C3314300003426F56BFC427C +:10A5A0000000901EC4BCC642000040E59C309242B0 +:10A5B000000000A2941A5D42000000E8764827429D +:10A5C000000000205FA0F2410000000065CDBD4109 +:10A5D0000000000084D7874100000000D0125341E2 +:10A5E0000000000080841E4100000000006AE84076 +:10A5F000000000000088B3400000000000407F40E1 +:10A60000000000000000494000000000000014406D +:10A610009A9999999999B93F7B14AE47E17A843F09 +:10A620002D431CEBE2361A3F3A8C30E28E79453EE0 +:10A63000BC89D897B2D29C3C33A7A8D523F6493918 +:10A640003DA7F444FD0FA5329D978CCF08BA5B253A +:10A65000436FAC642806C80A0000000000002440D4 +:10A660000000000000005940000000000088C340C6 +:10A670000000000084D797410080E03779C3414350 +:10A68000176E05B5B5B89346F5F93FE9034F384D58 +:10A69000321D30F94877825A3CBF737FDD4F157504 +:10A6A000505834424C76312E31362E306762353573 +:10A6B0003036653664333900050000002C002F6405 +:10A6C00065762F7474795330002F6465762F6E751C +:10A6D0006C6C00FF0000000000000000415F0008FB +:10A6E000455F00080000000000000000495F00080E +:10A6F00000000000AD6100085D6800084F600008C0 +:10A700004D6300080000000009660008816200082F +:10A71000000000002F6465762F74747941434D2545 +:10A720006400FFEC896C0008C76B0008856E0008A8 +:10A730007F6B0008A56A0008956A00083F6A000858 +:10A74000516A0008536A0008CF7500084D7100086F +:10A75000000000007B73000800000000B5730008D3 +:10A76000000000007175000800000000576A000832 +:10A7700042756C6B00486F6C7962726F0050583490 +:10A7800020424C204B616B75746548372D57696EBC +:10A790006700120100020200004062315000010116 +:10A7A000010203012379000823790008000000005A +:10A7B000137900080000000025732F257300FFECBB +:10A7C0001D830008B9810008F78000080000000020 +:10A7D000FF810008DB80000800000000000000008E +:10A7E0002F002F6465762F74747953302C313135F6 +:10A7F000323030002F6465762F74747941434D30C8 +:10A800000053544D33323F3F3F3F3F3F3F0053548F +:10A810004D333248375B347C355D780000000000F2 +:10A8200007B007B0020007B0000008B0263A09B030 +:08A8300098EDFF7F010000001C +:10A838000000000000000000000000000000000010 +:10A848000000000000000000000000000000000000 +:10A858000000000000002C01A40B002400000000F0 +:10A86800000058024C09002414A400080000002429 +:10A8780000000000000000000000000000000000D0 +:10A8880000000000000300080000000000C20100F2 +:10A8980035000000000E270700100140167C090053 +:10A8A8000A7C090000000000FFFFFFFFFFFFFFFF19 +:10A8B800A4A700088000002401000000FFFFFFFF9C +:10A8C8000000000000000000000000000000000080 +:10A8D80001000000C0A70008000000000000000000 +:10A8E800510400000000000000000000E00100002A +:10A8F8000000000001A800083F000000500400000C +:10A908000EA800083F000000010000000100000040 +:10A9180000200052000000080000000000000000B5 +:10A92800010000000021005200001008080000008B +:04A93800008000009B +:0400000508000000EF +:00000001FF diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index b1072f1693..4d55c5562c 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -181,6 +181,7 @@ - [Holybro Kakute H7v2](flight_controller/kakuteh7v2.md) - [Holybro Kakute H7mini](flight_controller/kakuteh7mini.md) - [Holybro Kakute H7](flight_controller/kakuteh7.md) + - [Holybro Kakute H7 Wing](flight_controller/kakuteh7-wing.md) - [Holybro Durandal](flight_controller/durandal.md) - [Wiring Quickstart](assembly/quick_start_durandal.md) - [Holybro Pix32 v5](flight_controller/holybro_pix32_v5.md) diff --git a/docs/en/_sidebar.md b/docs/en/_sidebar.md index 3e7246d6d0..6d5a2976c7 100644 --- a/docs/en/_sidebar.md +++ b/docs/en/_sidebar.md @@ -182,6 +182,7 @@ - [Holybro Kakute H7v2](/flight_controller/kakuteh7v2.md) - [Holybro Kakute H7mini](/flight_controller/kakuteh7mini.md) - [Holybro Kakute H7](/flight_controller/kakuteh7.md) + - [Holybro Kakute H7 Wing](flight_controller/kakuteh7-wing.md) - [Holybro Durandal](/flight_controller/durandal.md) - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) diff --git a/docs/en/flight_controller/kakuteh7-wing.md b/docs/en/flight_controller/kakuteh7-wing.md new file mode 100644 index 0000000000..5d9a29cea6 --- /dev/null +++ b/docs/en/flight_controller/kakuteh7-wing.md @@ -0,0 +1,86 @@ +# Holybro Kakute H7 V2 + +:::warning +PX4 does not manufacture this (or any) autopilot. +Contact the [manufacturer](https://holybro.com/) for hardware support or compliance issues. +::: + +The [Holybro Kakute H743 Wing](https://holybro.com/products/kakute-h743-wing) is a fully featured flight controller specifically aimed at fixed-wing and VTOL applications. It has the STM32 H743 Processor running at 480 MHz and CAN Bus support, along with dual camera support & switch, ON/OFF Pit Switch, 5V, 6V/8V, 9V/12 BEC, and plug-and-play GPS, CAN, I2C ports. + + +::: info +This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +## Where to Buy + +The board can be bought from one of the following shops (for example): + +- [Holybro](https://holybro.com/products/kakute-h743-wing) + + +## Connectors and Pins + +| Pin | Function | PX4 default | +| ---------------- | --------------------------------- | -------------------------- | +| GPS 1 | USART1 and I2C1 | GPS1 | +| R2, T2 | USART2 RX and TX | GPS2 | +| R3, T3 | USART3 RX and TX | TELEM1 | +| R5, T5 | USART5 RX and TX | TELEM2 | +| R6, T6 | USART6 RX and TX | RC (PPM, SBUS, etc.) input | +| R7, T7, RTS, CTS | UART7 RX and TX with flow control | TELEM3 | +| R8, T8 | UART8 RX and TX | Console | +| Buz-, Buz+ | Piezo buzzer | | +| M1 to M14 | Motor signal outputs | | + + + +## PX4 Bootloader Update + +The board comes pre-installed with [Betaflight](https://github.com/betaflight/betaflight/wiki). +Before the PX4 firmware can be installed, the _PX4 bootloader_ must be flashed. +Download the [holybro_kakuteh7-wing.hex](https://github.com/PX4/PX4-Autopilot/raw/main/docs/assets/flight_controller/kakuteh7-wing/holybro_kakuteh7-wing_bootloader.hex) bootloader binary and read [this page](../advanced_config/bootloader_update_from_betaflight.md) for flashing instructions. + +## Building Firmware + +To [build PX4](../dev_setup/building_px4.md) for this target: + +``` +make holybro_kakuteh7-wing_default +``` + +## Installing PX4 Firmware + +::: info +KakuteH7-wing is supported with PX4 master & PX4 v1.16 or newer.. +Prior to that release you will need to manually build and install the firmware. +::: + +Firmware can be manually installed in any of the normal ways: + +- Build and upload the source: + + ``` + make holybro_kakuteh7-wing_default upload + ``` + +- [Load the firmware](../config/firmware.md) using _QGroundControl_. + You can use either pre-built firmware or your own custom firmware. + +## Serial Port Mapping + +| UART | Device | Port | Default function | +| ------ | ---------- | --------------------- | ---------------- | +| USART1 | /dev/ttyS0 | GPS 1 | GPS1 | +| USART2 | /dev/ttyS1 | R2, T2 | GPS2 | +| USART3 | /dev/ttyS2 | R3, T3 | TELEM1 | +| UART5 | /dev/ttyS3 | R5, T5 | TELEM2 | +| USART6 | /dev/ttyS4 | R6, (T6) | RC input | +| UART7 | /dev/ttyS5 | R7, T7, RTS, CTS | TELEM3 | +| UART8 | /dev/ttyS6 | R8, T8 | Console | + +## Debug Port + +### System Console + +UART8 RX and TX are configured for use as the [System Console](../debug/system_console.md). diff --git a/platforms/nuttx/src/px4/stm/stm32_common/hrt/hrt.c b/platforms/nuttx/src/px4/stm/stm32_common/hrt/hrt.c index 86d806b4f6..d0cda2e8db 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/hrt/hrt.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/hrt/hrt.c @@ -232,7 +232,6 @@ /* * Specific registers and bits used by HRT sub-functions */ -/* FIXME! There is an interaction in the CCMR registers that prevents using Chan 1 as the timer and chan 2 as the PPM*/ #if HRT_TIMER_CHANNEL == 1 # define rCCR_HRT rCCR1 /* compare register for HRT */ # define DIER_HRT GTIM_DIER_CC1IE /* interrupt enable for HRT */ @@ -306,13 +305,12 @@ int hrt_ioctl(unsigned int cmd, unsigned long arg); # define GTIM_CCER_CC4NP 0 # define PPM_EDGE_FLIP # endif -/* FIXME! There is an interaction in the CCMR registers that prevents using Chan 1 as the timer and chan 2 as the PPM*/ # if HRT_PPM_CHANNEL == 1 # define rCCR_PPM rCCR1 /* capture register for PPM */ # define DIER_PPM GTIM_DIER_CC1IE /* capture interrupt (non-DMA mode) */ # define SR_INT_PPM GTIM_SR_CC1IF /* capture interrupt (non-DMA mode) */ # define SR_OVF_PPM GTIM_SR_CC1OF /* capture overflow (non-DMA mode) */ -# define CCMR1_PPM 1 /* not on TI1/TI2 */ +# define CCMR1_PPM (1 << 0) /* not on TI1/TI2 */ # define CCMR2_PPM 0 /* on TI3, not on TI4 */ # define CCER_PPM (GTIM_CCER_CC1E | GTIM_CCER_CC1P | GTIM_CCER_CC1NP) /* CC1, both edges */ # define CCER_PPM_FLIP GTIM_CCER_CC1P @@ -321,7 +319,7 @@ int hrt_ioctl(unsigned int cmd, unsigned long arg); # define DIER_PPM GTIM_DIER_CC2IE /* capture interrupt (non-DMA mode) */ # define SR_INT_PPM GTIM_SR_CC2IF /* capture interrupt (non-DMA mode) */ # define SR_OVF_PPM GTIM_SR_CC2OF /* capture overflow (non-DMA mode) */ -# define CCMR1_PPM 2 /* not on TI1/TI2 */ +# define CCMR1_PPM (1 << 8) /* not on TI1/TI2 */ # define CCMR2_PPM 0 /* on TI3, not on TI4 */ # define CCER_PPM (GTIM_CCER_CC2E | GTIM_CCER_CC2P | GTIM_CCER_CC2NP) /* CC2, both edges */ # define CCER_PPM_FLIP GTIM_CCER_CC2P @@ -331,7 +329,7 @@ int hrt_ioctl(unsigned int cmd, unsigned long arg); # define SR_INT_PPM GTIM_SR_CC3IF /* capture interrupt (non-DMA mode) */ # define SR_OVF_PPM GTIM_SR_CC3OF /* capture overflow (non-DMA mode) */ # define CCMR1_PPM 0 /* not on TI1/TI2 */ -# define CCMR2_PPM 1 /* on TI3, not on TI4 */ +# define CCMR2_PPM (1 << 0) /* on TI3, not on TI4 */ # define CCER_PPM (GTIM_CCER_CC3E | GTIM_CCER_CC3P | GTIM_CCER_CC3NP) /* CC3, both edges */ # define CCER_PPM_FLIP GTIM_CCER_CC3P # elif HRT_PPM_CHANNEL == 4 @@ -340,7 +338,7 @@ int hrt_ioctl(unsigned int cmd, unsigned long arg); # define SR_INT_PPM GTIM_SR_CC4IF /* capture interrupt (non-DMA mode) */ # define SR_OVF_PPM GTIM_SR_CC4OF /* capture overflow (non-DMA mode) */ # define CCMR1_PPM 0 /* not on TI1/TI2 */ -# define CCMR2_PPM 2 /* on TI3, not on TI4 */ +# define CCMR2_PPM (1 << 8) /* on TI3, not on TI4 */ # define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */ # define CCER_PPM_FLIP GTIM_CCER_CC4P # else diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index 538cb9d8ed..a86ade0ad0 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -108,6 +108,18 @@ RCInput::init() #ifdef GPIO_PPM_IN // disable CPPM input by mapping it away from the timer capture input px4_arch_unconfiggpio(GPIO_PPM_IN); + +#ifdef RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX + + // If we use the same STM32 pin for PPM input as well as serial input, we + // need to configure the serial port, as long as we're actually using that + // serial device. + if (strcmp(_device, RC_SERIAL_PORT) == 0) { + px4_arch_configgpio(RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX); + } + +#endif // RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX + #endif // GPIO_PPM_IN rc_io_invert(false); @@ -661,6 +673,15 @@ void RCInput::Run() #ifdef HRT_PPM_CHANNEL if (_rc_scan_begin == 0) { _rc_scan_begin = cycle_timestamp; + +#ifdef RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX + + if (strcmp(_device, RC_SERIAL_PORT) == 0) { + px4_arch_unconfiggpio(RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX); + } + +#endif // RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX + // Configure timer input pin for CPPM px4_arch_configgpio(GPIO_PPM_IN); @@ -684,6 +705,15 @@ void RCInput::Run() } else { // disable CPPM input by mapping it away from the timer capture input px4_arch_unconfiggpio(GPIO_PPM_IN); + +#ifdef RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX + + if (strcmp(_device, RC_SERIAL_PORT) == 0) { + px4_arch_configgpio(RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX); + } + +#endif // RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX + // Scan the next protocol set_rc_scan_state(RC_SCAN_CRSF); }