From 47cb1133c319a23c0bf344091f8c3fcb249d718c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 3 Apr 2025 06:57:47 +1300 Subject: [PATCH] boards: add new target for Kakute H7 with dual IMU --- .vscode/cmake-variants.yaml | 5 + .../kakuteh7dualimu/bootloader.px4board | 3 + .../holybro/kakuteh7dualimu/default.px4board | 92 ++++ .../extras/holybro_kakuteh7_bootloader.bin | Bin 0 -> 41876 bytes .../holybro_kakuteh7dualimu_bootloader.bin | Bin 0 -> 41844 bytes .../kakuteh7dualimu/firmware.prototype | 13 + .../kakuteh7dualimu/init/rc.board_defaults | 30 ++ .../kakuteh7dualimu/init/rc.board_extras | 12 + .../kakuteh7dualimu/init/rc.board_sensors | 13 + .../nuttx-config/bootloader/defconfig | 90 ++++ .../nuttx-config/include/board.h | 433 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 46 ++ .../nuttx-config/nsh/defconfig | 252 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++++ .../nuttx-config/scripts/script.ld | 228 +++++++++ .../kakuteh7dualimu/src/CMakeLists.txt | 68 +++ .../kakuteh7dualimu/src/board_config.h | 225 +++++++++ .../kakuteh7dualimu/src/bootloader_main.c | 75 +++ .../holybro/kakuteh7dualimu/src/hw_config.h | 125 +++++ boards/holybro/kakuteh7dualimu/src/i2c.cpp | 38 ++ boards/holybro/kakuteh7dualimu/src/init.c | 266 +++++++++++ boards/holybro/kakuteh7dualimu/src/led.c | 218 +++++++++ boards/holybro/kakuteh7dualimu/src/sdio.c | 177 +++++++ boards/holybro/kakuteh7dualimu/src/spi.cpp | 50 ++ .../kakuteh7dualimu/src/timer_config.cpp | 55 +++ boards/holybro/kakuteh7dualimu/src/usb.c | 105 +++++ 26 files changed, 2834 insertions(+) create mode 100644 boards/holybro/kakuteh7dualimu/bootloader.px4board create mode 100644 boards/holybro/kakuteh7dualimu/default.px4board create mode 100755 boards/holybro/kakuteh7dualimu/extras/holybro_kakuteh7_bootloader.bin create mode 100755 boards/holybro/kakuteh7dualimu/extras/holybro_kakuteh7dualimu_bootloader.bin create mode 100644 boards/holybro/kakuteh7dualimu/firmware.prototype create mode 100644 boards/holybro/kakuteh7dualimu/init/rc.board_defaults create mode 100644 boards/holybro/kakuteh7dualimu/init/rc.board_extras create mode 100644 boards/holybro/kakuteh7dualimu/init/rc.board_sensors create mode 100644 boards/holybro/kakuteh7dualimu/nuttx-config/bootloader/defconfig create mode 100644 boards/holybro/kakuteh7dualimu/nuttx-config/include/board.h create mode 100644 boards/holybro/kakuteh7dualimu/nuttx-config/include/board_dma_map.h create mode 100644 boards/holybro/kakuteh7dualimu/nuttx-config/nsh/defconfig create mode 100644 boards/holybro/kakuteh7dualimu/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/holybro/kakuteh7dualimu/nuttx-config/scripts/script.ld create mode 100644 boards/holybro/kakuteh7dualimu/src/CMakeLists.txt create mode 100644 boards/holybro/kakuteh7dualimu/src/board_config.h create mode 100644 boards/holybro/kakuteh7dualimu/src/bootloader_main.c create mode 100644 boards/holybro/kakuteh7dualimu/src/hw_config.h create mode 100644 boards/holybro/kakuteh7dualimu/src/i2c.cpp create mode 100644 boards/holybro/kakuteh7dualimu/src/init.c create mode 100644 boards/holybro/kakuteh7dualimu/src/led.c create mode 100644 boards/holybro/kakuteh7dualimu/src/sdio.c create mode 100644 boards/holybro/kakuteh7dualimu/src/spi.cpp create mode 100644 boards/holybro/kakuteh7dualimu/src/timer_config.cpp create mode 100644 boards/holybro/kakuteh7dualimu/src/usb.c diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 5e37372b96..741bf8f4e0 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -301,6 +301,11 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: holybro_durandal-v1_default + holybro_kakuteh7dualimu_default: + short: holybro_kakuteh7dualimu + buildType: MinSizeRel + settings: + CONFIG: holybro_kakuteh7dualimu_default matek_h743-slim_default: short: matek_h743-slim buildType: MinSizeRel diff --git a/boards/holybro/kakuteh7dualimu/bootloader.px4board b/boards/holybro/kakuteh7dualimu/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/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/kakuteh7dualimu/default.px4board b/boards/holybro/kakuteh7dualimu/default.px4board new file mode 100644 index 0000000000..fbecd9f5af --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/default.px4board @@ -0,0 +1,92 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS2" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS5" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_DRIVERS_OSD_ATXXXX=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=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_INTERFACES=1 +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=6 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +# CONFIG_EKF2_AUX_GLOBAL_POSITION is not set +# CONFIG_EKF2_AUXVEL is not set +# CONFIG_EKF2_BARO_COMPENSATION is not set +# CONFIG_EKF2_DRAG_FUSION is not set +# CONFIG_EKF2_GNSS_YAW is not set +# CONFIG_EKF2_SIDESLIP is not set +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_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_GPIO=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/kakuteh7dualimu/extras/holybro_kakuteh7_bootloader.bin b/boards/holybro/kakuteh7dualimu/extras/holybro_kakuteh7_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..7f5d2b31afa554e5854fa7bb7498b2a090cb8760 GIT binary patch literal 41876 zcmeFZdwf$>);GS-CCTXpn$jYnEs#r#ZBsO~s6})PNjbd)Z2=v*I2tJWoKgoWprSI6 zQq(FsgP;yj9T9Y7M5QTY#)7p~@HRd^PXg4ZQj`kFffnV27IJ#c@4FM~%&7CezxTiQ zk2jys$=>Ijb@pZLwbov1?X`Edfuw6VBK(E@f7k!R!T&upK(744=Re%^o8M_Zy3noh zj92&s)_e_Cj}J&3Hwh5Z^rMd;QZJ>nEKXD6J4rsF{AEEbXg5J5U;Z zTYp~vwB1I(k8k#L3$>o^nA)1|#M-Jt!jp8tH{LbA=vdkZ<42{K6^`BNsBI=@Vj{}x z17lq&KYMdkF;QyziIUn&lsSDwS<&0vUHXUS?qz={RXQw3)Q#7g6^1>C^oaWWmHhM9 z4#N=T!vUhi;=8~AX})PRNhi#ei;(o^cMzefWL^DXl}xepcr4ByPu_>f-|u2JGj+sD zxO-+tIeU z^nN++mmfs_h+0PR;&AkM@V;#L-i-U)=sn;SyjSRZ3LhzN6uuwzPvrsjN?D2>aAoOi zeN`bHtvc?OOSyZPI%ZmyOqz+Eom=$2iHtHD$-^wCyOw2`TA`T`BblxDWz8f;#(WfC zITeOGgfzo-P!&vvR6U>W!t?YbyHn9e-k4m6)SM|4meK=-J*2vMqCBdGL!CoM)i#tt z%A@790q!{7A4hr==~1K|c<-6xR9-=89k@S>=Vy_gM|vKqf>c3z8tG}IJxF_|=$oQ_ zARaR7KQ0V)5)x*r3d84Z`@nPSiN#~S(59I%%CnvkmO0AKu}%sq~W)89B%N%-Wo4jrMSj4G0V+tB+4Z~SvWc5;^%I^*1oh3n&clHJ6Z)^SUY(3UpSmY-G-A9+p`z5AkkPY&N^ zm{}Hi+AXie-RPNBk-PKq3pwmprApYQZ%UlGG4kxBtatI5ac(Y93MrT5J}hf8S>#Ec zDr+M-kEL5q$UGI$xoGX6m1h21(jnlA$EC-W{yowTJoC|B8H;HR3nWfS;O3`s!FNLu`U4cgPz*jBSE_g>LmG{PJj7)jH-||oiS~1`)1mUIn*ptN5wpHH&Y0pR z%3u44d1NtXB#O5WrI-(^X*XMxwN9tf;rtMJ#X{+3(O-oo588yOOCYC72gUoj7$P*{ zO7eLu%$pS=FNQ;is88*eO%1J)*BiyuKfQxmexO?TQ z!f1bws5z64sF^p@d64{!C*L+PMMSy2*Ygq){=SsS7JP!A&5re_G#)hz%ZOr9iBV{Z zUB zv+9KHxON0H+05+Fu@mY`-kloH9%0r`d5$?C_p7knOlk$mJuKPtuTEh1@DK z200Zum5ib}203N~&2h+a0?p}=({VJHfLub;S!Du?`GsUdST_x~kh$^S-$ncVf6~9q z?CaWTA5rH7qsmSz?M!km?w;T*?MyDXw|hcCY3Jw}_jOO0QQCQx_#fR9#L~_&g;Mu~ z!qQGdQAPKJqSDT>#Y?&;6qk0UlvH+4C@Jksb=}`R!A09&+L<;JWquyT*%!xXfB5V_ zwo`l!*G1DEL7v?&5BKkXH5z<&`0}bf^m{sPXsczooai|6EclWbV~JqHCHNTSZ~Y87 z1vFt4d_*BC{fEAk?eyyvCV>;D`k5O!l}Tl?^S@Gj(>s}rKk43Xu=?2>Eh@W!%Qk#< zmu^OOvZB4tQhHtzwjzKJYxlDc|<;mOOW!#8_v1 zZIe8NQ!e*ry9{{3yNyM!t|f}lzf&4t)GpoQW|YMPso>&ZUkd(H@LXd~Sx(Foz_T1m zB}$8`Rn&nrSDcq9x&5g~bxKlyO61-XW|WtD8D(8RuXKfZOH2{{BBfsw`EshNjih^2 zM!9xiK+cmEkOuI-9{m3nt}T!orV$uZNFdaX_6ptiA4`5!;tnz8Z zcrm37a_tGowV%xPX^r8~or7jkH&ZCO++bI)vy-lmh{OE^WH3gwX_+#b^rIi91R`{x zov&vKzWBD7lG&=ww!q7FwXn0LErnWFiiFE8G!e7Lby-dk={FR9xUckkf$9vuAX~48 zYz>EMhr(#D#+52ry_%9y(x}FiXPDfS^%1&irsYssn&i^^Qlt;PqX4(Nk?J5n?NLLo z(MGH>$B89reJr5nG)8qLV$?S=)9Mw!#x+jm3=O5EAw3J*01r7JeMUBB~R6i*BpappuDAKirV_BCZqVB zM3jenL-H~uPSYb#@M&Knn_^KOGlf{jg4(|b^BBVkKHW>~^V*lbI7g-=iLoMU3Wr)E zZ<2icm8ZlU4t0g;h)+7#UHHV>T2UiDCr%b8h+nIj+X-lqAAe&z>Qy)`QQB}9-~Oa` zwm4PH1P}W9`0*ONg>H*CNyqN=()^!$O&z)7tO&$$JpbX??n+_}`X@)86!x8$0LNR%X%AAhnve%o}sCCYZ(wMR<)T`#3XNW&*d^SC4;Oga}T<;9UAvuUe{5qa|G zv*!tQU^_0)F_n}NW1C8B%ys!CiBhd&M7v&U0oSIgQ%W=<$(#`gH#`a21OCX=4rWrK z^lmeg!A#Av&rwbFTvzqT13{8-ZQ#FDVh=Zb=l(lNr0`7L<%XA4n{l4V87Ho!v(9}h zAxWm5+F()2xg;kaEMQO7Kz5?->(#V+M!CB$9Qt%<3?vMvybUR0c{m*M56y+1ho1d` zxsI{DBPU9w3W*=#Dkh2U6bbDnY}euC?{zIo;M-Zn8~zlvKQEW5IV3*F#HUCfNX(6~ z_8F>~$e@49-!I{!{7w0Mii={3WF=vZ`N9 zyY)bh$WF-@wO#8OMtQbZi+O9kKr##bq)Uk16%>TMB7buWrsE>C{+@nbtS=}QnJHzs zo6>)KLEDVf05O)ReEfdtu=Hzpv`_YnjNuM7osdkwpHm9@8QWu(+JZkht~$(2DVPxq zEK{`Poa|Eh(mPas0wno!oHDt;T4c5w#h4%y!ztSSnFW5(_I%PxDV!XZ$Gl7g{je?Y z6FY`cZtsoqp1vvHm*h&5PHo^6j$^H?-w2A@4GGK`(W=CDX}&aDHQHQ_r#8G^5rq)~ ziQ=xpaOjBv##ZaN5MYd|%zzR(<$|h4`Bo%m!FRfWbD2Z~_-=Q<5tRR;N_krEGnjbX zT~LkQol?8RLDSYln#DnyRr!F=p5IroO2-f{ZiKAg+pihVgOge1lc7wps)-M#lYMTj zV(CLWGdSg7Z+C>F71@7|%}sGL=K0I33iEyIC5<@6TmC3x<-cO4l`kij-R^uy0ix8Q zEto@kX-VKvl*1{_ly8(5hq`2+7;&sii@)8rWCdE}~Sa&NN2U`3Z(%vK5wStQ!L z%s85_L%)b}jmp7y^BpjDX@D`FxKdBPuSP;29!DRHuuRbh&y_w9<4YAQz2--rc4z}! z(7@Ol1>j{vnC~!(=~7T;l|O{PZ=iOpQOs}B`?$wyqVvm7sCr~EtCWR@>6*312TJrh?xW@IMa1X^a5)38gJDaM=-EUNGnS~DGW5}c`_ zZ*K~hHS)pRBl+vY`Hg_dJ#;RSj->L=0CYuV_kbctztBgZEaA*X1Il5Q@nJ(FgfTDpav!nmTuhY3;fS6vabE{bUz4&{p)5+N6!-9GP~20G#?Fc)ui=qehY&d2 zK)oD!-fU^Udx^Bo-65w+iu`NL)BWB%idf~~kg@T0q|HMl^RVA4Io*{~jXN@;KWib6 zQT)DvRh}B6qjo_4<$l{(+}(=#_qaQTt2S)>?(YPw~5N=$^h>wU&Nyt>9;lfupoG5%W_uB$@VqWXoEO zl?(9Dqlq%A&$3o$y%4aj60GL~^vTD)XJx804b$C61|sNu%yUFp-ka%VwsQ5qQTeWL zsQdk83QHn){h*Q3C+m68&(T2+v!5pheTii@g9?Rxy=EJ`8SSs(UcvZ2x%{tBp=D2E zd{1uR{&=Ec6ug76emWboif@pqEg)^Hqne) zPu48D{|@`Q&Nz0o{qfE?l));sgPOXigo180Xahb*_iu-_A3m>v4w(k2_ZgM$%BWt- zq2bWs{Zvi~KGww;Q}MQ>H+t`pjNlbL=<#SXJdLpOiA5+G1&Lh^Ny2s=*8`cp*?8mxYf||^uB`|crjHo`sj^~9x2o7 z#C*pFa)6arA-9PV7nx^P4ba(U`{1b!&K^>JszwhP3Q49I@s?tkD7)UJk}n_pmkx~u z(j4motdcZHjOQ_HM(1X|?+|1R^~grQVwIu&={BO=yPsHeK2~HlGA09bUQ0i-jaalM z#;8@s^~2AzO>1J2AJb2aQA!S<=cqPX{qvb1wnQ(vy~H}QJqC6Lb7P9V3>urk`=PYW zVZa!F9+}r*%^G`Us<+WOlgij%9szDGKaI1(v#BiT<1ISyV)=TaOz(@1N`8|LYaf06 zA^G2FNksWzV0bpMdAZtDo;eE147BUk8L85F@WZ*fr#8{cTsT zFpByJ#EU;d4E9FLu%is&pCBHOK&VZ6%&`Vs@T2@F`~DsFxnjy~Qa|N3YFpE9sg^!k zEGwCS*%7M|^&`c0RoKpdMMop5Nl$N_Dwcst-+@+gZ{t-5i1DIKtUZA^_#uM+aOj6Y zlKFk$j67AG3!eCT&;}{Mm_Is4EG#s{Gjfi%96sfpQlvQHE5`=)3~&dXG920#{zN9`D9nEielH)TlB5QbI*x26bPmU;Zn!e4 zM$Dus{iKc;qmr=9OH0zhKDy9%uX}~G)4f+Z<$gsj1Kwx%CKvN!OGE=iDNjX9c?y!2 z1j|^Xm^=m6s)bb!_mOR}#m_sKx}HF^R9Ziw(z!PJO)YYQ_(4QRr}!k68+_{|hRz(1 z|I}K4z9OeF$|=ki>R~rM!t7#|Y5nQaMd&pn;N!J>heAE!^onG!W%X_c7Z?f+LZi)Z zN|!Fl;q#*)%Tpz%HxWI3y|1HDUli51UfCa^^PlMqx*|H>8~f;ZLsLS(zf=V;`0YV` z6P+uE=?41W@BSD1U*9mt{{Pnh-X+b$W&e9wqIjLsDKEU`n1R~8I~@rDiE-yUx8WOjR%PwX3!D-jWMGvQJ9L1V*LOzN zBE181_DSgacJyx*=B7GaALG*ei3mKjNX~sQsGq}KB9=HeBzW^`^nulucIuPjkJ6P4 zEj(8iV=ipI1j1OxdO55eZ(Il&YwMNmCuEp+Y!^p^^!iW``hAz|%N+jKFL{<6 z3lhzYu2{`pNz)f|i7`^hc(jG|3CfJlc#RJd=GwN`HIrI7CzG|po#a2INo?hnc)ql= zmP;`5!TJJDiRX^0Lh=^-D|S;SVG^8&RAFV*N+3pPAWyQUc`|3ZQ_d3akcn}POe|Yu z#`2=fW_&1f87;Dy1depUIUWx#_H6*C~yS z(KR2cJBHwANW7JK?pjH!Tn#%GIuGRcl%Wx{Jg-)ntQwt%8m4$-;XTdv_T85)9bO7g zbiLAKm2|=T$yZAwvkf$-H{PY?Q6D9hQLu3<aPj zV`5S&%0a7Y*9Kz5YVe${n*1hb;+j;RyJFC!6 z?Ui;`!Cv_KN1t>R#zQNP5R*lV_k#_L!ZG2{tKpo2Ofg;2@e5NwJ~#4?2QVTW)(ESh zM{V>S8dp}Lo7eF6f4)pWy)3TsioT%DQ0^A zpJk_(&WDChWvSlhT*`~wfmDp)I>)#`%1n!t)JW%Cp>SvLDEaW**d(L-sCg`~|3^>{ z7d(o!*ij`G>7csa=rPZS?&?`i>(Dn%zwfB|gQeB?y^8N>yVmxeS{jAdme6`BJgxcE z($hcs=_{_LcGU>@5*5qqOQS2rP@+7Cly>97diDF``^Eo%QU4B`A2#3D;(f6bH4pv5>e&#RRx-?co+!A3G zMkBbt`RzSR9}t+XLdM&FIk-6M#;=&kuv+cKf)Oy=mg?QxmImCL)nDr^B}^9EN!YxA zqo-xjX7x@IlgavpOk3cQy)@Pa<+`^l-K@@aPnS$R_E{snu%Ty7k35^_uBOi(81KD% z8GY_~pxT}7tXq1zA;nF#9i{1mZU<{p5*Rz`j^ShC6P+zGnz&7ya)_o9=aXvdmKrw7lHm@)Qqq>Bq8K zP!{$5{icHI5?dYTD>Z)arRud={$+}Rfa|ko`kz;SZR__kRzyfV5Z_$dLsmdba6Yfj z)$2v-mA9LSiQdoC(>r+nr_+0ANDc*ITd<4^=*|y2)VZ_hDkDxx|R&JQPaXpYQvqQd^uYzJRAgp=8)dhDMqn3_TOk zhO4tFZzhYImL937YuKWFO`UB^YTXAae@dIsO1;l}hxXxFidIXX+ETS_~m0Bko)})=lYS zylWd|6|ia^S2P&9IM}f?99qzCTow+^?RPH|yy4L8{X3RYJkOCVJ-?e1Uc&re*p`YB3i&AT>$W*`=>vdId3%N$; zLSk_(EMH?>bFjNbV{Gh@$ZB`@L9YCv&*2d%soqjpzUJP@eSXsom>FB7SkdFmkllvz%)_^jMTq$iwLmachV%rkD%rS;i7j(~36R zEzS?rw0xz>BwECykQF3OuoJaAjBp)$hi{{5Xi2`Uv~%W|rg>I=%+cLkqAOaL72eYy z>*{<4V;ZgRz`xW-)-V=rNsXNt5glZRqj5p`9Ze*L){!?r>u|1ly0%^W*(y5QGOh68 zHitvcLg$;lhF$YH^nJ&unazSL#`TmgsQ}sr;tq=i42PUbFcT7i|TJe~DSAZj%dV-Q@{;%%h1Huc{i5|2_T{hE5qU29@M z10=~%K)uZ$td4UYTp9J>=$lx?X$nG1_Xw)70uS8kh27IRZYAx_mC}CVdl!oQDxW{y zYf)IP1-WQR6yAv^RHvZj(727_My#3{8Rb^^R}5YQymN!0zYoFx0-dFb;^r4t3AokA zw27^8Goi!hx9j3tkE;A!jd2F3F9UPmA=C%GO+`BQa>H;;0j;mf=UPMK5*Fyyj#0f?6@& zdP=XE>*}>%!#h^Y=fz4}9L%P^<1`kL=mopY$3Y)V8JC)})j^Kip!*%{)@86Ne-o>6 zcOgFmS2?S)cd;sSQxe7*c*J)amllz|dMjc#t+XA8?6soA2#(=?ck3;hlB9(iS7OCy zTIjUX`U0GBF!b946eso(9I-1#qAAh3^a~R!p86+W7=vC|OB8Eg4EBK1u2A())_0aEzm3e#ZIStu&H`0F=Nex8Mtf5$ zx8_&H3z!9S$MI8I@%1nHo!87}=FGJ~QaF{3&N*dyCES{M4BO>QGDsfXKhHAzky zgW>Ev?~N(HEYHievL-qG>aK#($0B8U=;cw%>7<-dviqQVLr1c9w(Oz zDs^ts@0>+tY%0eE@$3>~S?6GnD@{!Lf6KE}qn)v(xi86j+NLY*qPCIS77pzV^XBr^ zl(NfLQY}0jdjEZ5PQ=*%(5(7KR_MTEcQ?kZv0*$ZXOKmdGwzFUm)g`_o7(6CpV&Fq zL%B~~s(sTT94TKjPpdf!AG|3#-|c>{e9hY_%etRPB9qD=iv9Xj?QVzexFL`i@g`9& zvxCb_YsR`tn8S0s(l#|TbnQ%tJ$6+IV>zr&5jKD`KUAmWeP_YvybJa`dlP#>H@@|0yn3tn#%; z8-~{ge+;GV%wXk`fmYpmeir@~W8h>`k+4ugtvXHpI2L*&AttA{!y17=~9*p4`; zAxq9}lS)YjZ0p!kB`xOEO3Q;W{hA`1_z7Y)D7_)w!CV&(jT_pcK4Q}b50MBJDl<9b z4Qbcc;#oM9fOj`f)=jeDX)SVJ2S&T-$}cgEE~0V&r3y0&(YBd!W<)Y)LfT*_0Le7> z3@w7R$+Vj-Pg{DbphfYVWgTm=EDwjSAFxB3>x#mmepu%UqAGS%9R~FM=?M7rM`GOz zcs-9aA3i!>{CC_IUrc!o^y>sKCe0}u4C#9*Y{btH;V?R)0_Y*4n_b}_#~MyNtYwZu zcWP$WXp3euiF0AMBqkyjX#N@p_FBw;C?X@#hJPomvY!Cusb9a5SU`Rss8`cI;EfRP9s8>i4Os#)Q5nhn`ojY7rW)YIrXgpD?j4 z;i4eSRdW>5eBJd#xPWU0uEHCl>32x8@}t*eq@}pNxGs9#3OM6xQOCEk*=%6Emb8x9 zJFK}`R=4Y}YJFZ^Wy=(wiSjOVnE7S2?G(f7Bb1UE9)=HxuoDKF@!d9zZ#Ab(;23MR zAKqy{u^tVOtiu6#CX--ukyjtKcRGpt;n5w?c{r{0qqc)s!%Wa(t&lD4tl?%hyYr~d zVkuZaHBqkoVXXB(4BawVLMt&O#g36N{o_LT2IsYIK3 z%jLWGv~;zQkxYcttIezL)?Lw z*qy7HseD#)+ljN#7vn}GBoYR)hU0dwr1&#(AIhxxvdo!#WZryH)|eG}*^h6j9^EBR zMw=$@={|EzyS8W2p0Z9Yx3(v1&)REmxjb=C`D*G}X05mM826Y!Xnuvoo@}=$=gMJuSzw*5p#1Q;nv6Bq-JT3C zp%t)FJ7&o7_Uq&A%3B`X=Z8&ON>byob4q#Hb00UV^+jlXZiv{Pg!%zo_2y>V8BL+LcAsU#hkT9>W+aoF46* zUu~bXThs-|kzMcs*yASjZ3r^Yg+rJ7Uhj&7EIHlxB4h|_&KH+p7JUNw$0GCZV=I}h zZ@?DAoIIFj;re50sT5xZ7%IcdTxkxXR8)sU#|Eyft^c7-$F%CDME3&0m^)V{SBtlH z>!xGhS7~SA*m){v#7O0{ot$7mr1u0wt4u2ygL$P`Wo?zK9pE~Jb6b-Ft?Crh`~xqb z4yrRhj+Evx-!U4*M*Xd?5*7m0dkqSk!1-BAb_p%Ppa=n(Njabd667$YM!D5cQ zeMry+8QtFkdU=*;!L0EYm6mBlr2IPWRq!#b1#?*6XL6MC{ed(i>5o-3T_pAx+7o-} zrAKocx2YN%ZPU|8n`O%X#FSaUYz&90Rr-$ELa{?*`X~hAxO(4`zt)k~C`L}7p?Vjc zqv+g3=P9E15IRSlP(Q7PcP8e9dg#?%SV?B;+H}8dtwij8aq3}JpAW4=V$2KF*ebR! z=3=gc-DIFT7dOE^2DHs>&iAu*_w+q=G0ilwlhgjj#q_hYuy;pdEbhrJH5S+<*|$aT zTV@>*!OZ;r7a(tkaXR8hoMx|n4%W}iqGjDPM(th=JIerkjHI%IQL32fog))raT&5# z?p}GLj%^hzwDf*x?9*D(VTc+jxvG>C>`A-eiPLr-rF%-Px*wuWEIHB(eb$aC8 zu2jTQ_D+4Ow%`p_@ci|Rv1ImYR#8|z4RqRJoc;PD)QNoT*&RnpJrxzxL9Rx8q76^`=^S!q7W(9MuUS`KD4ncVZ_Q z)s>FGw^Ie*Ld%>Z?)~5WRQJgD#m($+n?w#PEn5mTus@0A6g))vO%ECeLMcNG;wr+S z->X!g>4r{5>7nXMOonG7u|zFsYGG0f8hTlORJR*>D{KuZOI(0bqju20LOy6b-7paP zauAe>^6yp!@m$1PS_SUt zcs9-zHd4*)aszfs#o&s=eo&;DNQ;mbA(fCyNNbVSBHe{_7t&9Wei{eAlp7iz^uAGGt=EBBCza)XLS1L2Z>QY0rn-OmX{%64iHDjnB6zWCds+BM=Y1h|izL^tV1$ zWWRbS^mK1+(NO5g$p8A@CvOXfo(eyS-2^?$>DtLa=!>EC#jMDQ&|~8rsymet9qu9X zhb!3!i8;QXO-{?Zd-2$N`QR!IbP{_3H0b-Qjy5p4HR@gV#mZVEYBYJ&c$2Q58^z>pQg5EFv(hitA-7!}IqPhI zn9GYP4QvZj&sNkXnbLgEOpoQBTX!OUg3{V4HwTEn_ggC9jcsRc4h1X~PVl;A;jdkH z%rsXVhNO+!+9YEj^w<8KmC1BvEN>@PW!_XRQm)adv~U)b27Jw-`t2znSjaxRQv`&jd3LxZCglbZ@zn8MM{ZDSv%d-vzoy*-K2yW zMDUvCFC1O6ZDF-}n|mnq?GXHDy$@o=RkaU<7QILJh{nAoka%3N@5GSf@L5uRXhHfi zbXZDb)ECh~?J;^mR(Ifv9jJ!{jwi#rKFKChSL0xg{9}(N_Z7kJPO|ypm7SVBGW?(- zS44L<%~o0L-9dz1vx<7^6G%Fu@glL^pCEqXpYKz#&ic>yRafrSNX*Dph|QU=YJwBE zh0>d2g$xVyGiD;)*}XHU*ZEVK0)76WbIcfu*H@+6+&hB;<5Y$C9YKNI>h8d9Plqbp zHAfY0Iw|Ej=YSSyEH%Xq+W0OLOyG80+OeFLTIIXlV1V~{2e@XOcshl6BF3xii0paFu`Y2=YIq;e9mb{`MPMzJ#z^T}e3 zIj#{ql^UxGqie<*QIO(M_h{9Trs-lwVXhv%yTalfDK*hTOtuih$*9cix7P@95vpm z+D+{ZX7@*`eL7vKt7^I({|OOQI`# zjB}QIY-FCT29BG~(ly(a@QG-}1RBZr3sLUG>_~UP%Mpy7Bg?+$F?qND(EDdYBh<<&=fY&VTl-_h?9XTm&cE@>7O2^z5X>MvlX8c!{ zf`wzl#~8?D7a*)&8cDR-(HB5G=et#f9Cl%)NUWP}bYR6V#cdF) z3S%Wsn(cLY>37h-*wM{nr6M=uX5G>Ev`&}gbjM=vRAK`fXll`K8?9 zQ4Oqzdat9gk%I4Ep9}DRJ{-OZErIN_h2%`H2{D!MtToVhpy)R=p0fK&JY_iK4*w&b zazfTCSi7S>eol&WZfoY;#2EeNpWkfwmp8Q66gv~LUT!ARr;rc~d^$94GhrY0f9;-w z6(Q`T*~}^ThPiEJHfAeP9#J)s*lVl^fs=UAhIsR%Ds-H2WFk?_$nn84LX>fl+)KzA zRGcIu+`~wtqe35>~d7E?=)&No3-L3sY}+1-^;4c2|1D=66>$p z>m#r?BKGS&^?uOm4;A|yx`-q?qMom)s92mr>CU?3CC9|T^{Kg{NtCd@c?+WCM;v=W z72$DUVOfaK(LWpFrNs_f<6qU&GGB0gN`jYM^WE{viirhX3->vW`nxLTr*$q&RvBwb z)n%EapOu#>0{>sK&G!`I%12OHzY7+k@-ZYTQC6y1BD0O|`?#-H1D`cfo`!6UfvgjJ zgQ0bhc681cz`M`9FCf~3F(anfl!KPAbQZl1`)7hSaxWqtX56?Dw@ z4Kg;)e@bHT6vkeI#?w8|SpT?%SbMP#m=pEBP2Si70a2TbZ6jheiP%udK&d6h()!VY82g_`}rj0EiO$YVEKrO58g>pw?COUAdGRc8CPH2Rj^6!b&p z3bE!wu|T{fXJ*^}pf%xF{v@Qvgq!^PgO-F_{BH(rTzf-|wY056b6YdpFXR^}9-i&j z-Jt8(ADon61)MFRD^Q>?JX;6c?q)aBHhdX)GdKettmSR7L1Sz|54ruGzNh<=K?MS| zP_3{(cy9uBq6Ddrm6=@7<0<&8ftYJL3KW(vPKKI$;vg<-q^0>R9CjHwV6-&#FHcUv@1}`MO46MQGkCQXCYC z$<5PY2ZbjSWy*j@-16=I;C%^ed)DlU6;WP6f+;4bi%G~5c4aBLxXk7R(}DAB9QFtI zzpSPs0w9KEvK{^%I_J^k$f-#f#~4I;#w0262~Iz)DY==qaFzp(_+uvB8(o|(=IFaP zkHiSczNPTpAS0-OUlow6DI||QQN_?|nCrI`($aa1)dMA1>qvOO72mv3+#>$DONfc- z60`k*!B-+%cj!#1GAZUm#Qs@hn&o(}aq4FcR*BZ~oqVw2Yt^`& z+3a>P+tM7Vfh1A*3!fKPz-%4s1*MF&W##x&f_%a??VD!g9HUf2`_8sAb=ziS9*adQ znYx`_f?$ESkK6p$=IqYS6&eeZM_Wxm+wUSB;}>vNMN+{5$G+xp3b{I2iAhKcOcUXY z-dZ&Ng9hfgPhb^r!Ek;%+DL>p`J}d}naMjNQ(W+yHx}|Z6DS+H?qy(Pg7{O6Sg@Mh zDDoXK!SGaD1bbGA!cgc^k?t3qeGKh-Mps4S!8zFnkLaxF%8}_ou(lhzq=|X4tN?8r!tUrNc9%2ep(clLh8_ zt3O;S1PYx0M80!!90?crRZa{$Lx+` z+%4>y&P+hN$AX8oeu_6PP}a$CI5o^8ycKIPLpER6%cq`hpb*USM0wYfr7*DtGbTX# zc`okr6kOD^kbB)RohRe&|A51D@sOuK1!r#v{S7<2v@sN;TRJ`$cWQv6xYEv!2VOq9NK@Bp z(cIB&?{1llE0HwV8#c+b$K!sf$BH&)e{gOB?c)r{{$<>;hM4TawixRStaNb7Z5ajl zjV>s-{#8v(kdONc``4LPVmc{9sx3U>H)Ac@)6mjzNlsU;;$tln`qoEqrHSB*rMO~q z{K8vHWVSAK)vv9w0Tz}!yV)tFNV-i7Mk*ZIFmU+0V&Hr%Fv9qO^OA$I6X2``T$J2830p|J-#8+oz9pBZ(lkGF! z#jY-G!OR0pU0%U>apia0#hXzdxknphwN@#)d9G(e_tjiH4p}-1UYae1pAEP7rY(iP`pzaM zMD{>VI;T1jANWX`NNv!xW((#b%EP0@($3SXY}of>7M;)tyN6=3_leUYP%+1Cxv$O8 zK$~9CC2;3qbHWQzLuDG{zacj$->!6`h{SO;UbU1?{Ss?{!&E6mEaZI`o|G^*h zeTe~6=eNr>Hk*mg*ZrZ60g`cGEc7RF{sT8XaI-rSW&VeKSD@Mdp>z57a{Ui2kG=A} zvvS`L;$yTF_G>!Re=EQ8y&ca!j+FeHRs^wH5;7R$E8pK#`P}#V$BaMd9>d$n7n)Y= zUKptVp)l_Cu6PYIO_;hDlCUd~>&@u=ZUvKt)K`f%7uWSMxA}YWnC%B$+$-N_ zql8Z)<@4+PxN!*EQ3v7 z&lVSmWJ@vdSUN<4w)lB;rxs48h&5y1rpkPdJ>^5|#0}yZIq6Ej{GjHC1lFPOO^3X;_0~Ik%QBne#mYCS1m5$`S`Up&vFE3iXr|_N2u;SBB&$K z#$nfyO#V3Z2<*?M-kjK+z5unZ7U(WVthjI}13n$)7-9}!-(s(0f!_DDBMET{X{(rA zlA{I;DfBcD)#(BKTqQcNbDmLYc`>j-BmSwHhKQx7JxcdX(WmsSp<_tAZcp z_CbF9*<%-FJ-FA`Yl95D4ec6nj6zZ$#NT^KPTR2;uULIgAPvZ0p3|01N-<7i0u!!H zYin{~W^2A#%ogA1(!}(KcJ_5wG*k#(8s1v4+0ng_Kin9ckdXXUsi^B9CR%1AYUnxk z1vvgj*p{>viO{(}YUc}H!<=wXru5wFH;E;pf^u}A(MM3GtDt+~4-sq2);NSX*DL+8 z>6@Gt-S9m9y4Sd5QN>0F_LWpTuNLZ4VZ|Ogr!y1typ;87p%Gp+Wdv&Gj?uM)yL&s} z9YZ{FFEM^C8^m__&B(jdDjNY@hC`pjzsyoB*yuSf*d2l|L+!+pD`tsq3FTqG>mPAu z28A#{o^;8Mid=8hvSu-U;gI-lWZbeC_)u;>K+hG6aiy+GQU-C-CjCliI;iV|4Sp|n zmS1k?T&y{zss}bz6YPgW$s}Fx6K1+$&Ak9$?6+tQ-;P)@*lJ0LM=yuY6Abjpp8~E0 z@B(}oa(H{t$jx=koh~%3KtGswNXBAgIMj}Bb?wY`T9t|8CtV6Kb;M|K!vhPui9?H6 zD{WyBS{SWc?@L4!Ka)4kzeq|zJnY!75?pnN+$ZJON0qnDk$9L>-WcMP6+=Yn@8gu; zAwL6gft>PJ{8OtFXOJ{w#~5LSaF`L^!r7a8oV^w|^LFgDGJEMib7KMh&*QO6Qj0d^ zHSUxwjjRz-)ZtvqPV^A#E$G{O=o{;5b05PFvH{qX^ch{de#`ZTdXk~Td8GC0##M1I zw5f=FRIVC2q3+v};KeC0Rd}-rSib)6s!;Y6&ShaxwmNjR7iZ33{fa36v5o*Yw}$zR zJoLbe@SJkWH$!}#Y1#zq**0be_6H$`W5!$}EWmZkJlMH+{^MGB7Hv$#_~Fd2bzB`?!{9bA>?rMdv??6BFr*pZ za#5|OFkx8yM7dZkjpsAT#UH9qoQ0hkH!?Aq@TNsrkBSS^uUYPd%$x2hx*YlM#{b<# ziky}KUHUp;XOK5(H)?lF@t1(NbDJ?H_M1wQRwXswLOG&p z`o&QkYtrr_SHG=IWjRe;pl--H!ik!#MBK{xKXPL$tqo z?&ukMj*dE@-FOiGS*Yv;C{p{2hXfqxzlhkh)3Zv?`_JsE-67=ftq zX#bK7T>Nc7Bl0HAMhz(SmBB2LQfwWC$I9}u2>dF*SNe_Sn~TR}Xm<^Tz}F`9>VWE`$rAqCzZ9)7R|-I%U{~#ui}*74%A>h=P+{8K(?!H#w~#? z*A~Z3ffMR$^%P=8XIvaknNsEqMB(okm^4({GoJH(39f{hBvZidMouyJjwm*|IpvyOoEPLZP>mor z?pCMCAZ5E*oJ1AW+Ki#bx9fKw5M zLci;edhrb%oDv$iD95d0teU{gRZNb?&*ljJ#a{U2`Ezoy*3iKd?j9&^fWx;8k{7y!JXt4Dp-YJjObY)r9JJ- z*$p%gp#ao+89yB%%KBxC0@sfd4#^_M?0sbR+wx_*JUbI-l&qq;g~bgK=gcPBoL z6*rv2LihXAb6BEZjSrk$#VX;LlZ}jN2kKl{wP^`FC&3i#N4uwg2lgr!i<_1h5oblc zd{5)sQ>)4w$u);?z6?jckjX^4lYFiA0{&ykM>J19j93{pk|%P`+g%lWFej!6yTxz7 z$ypQHX~ZjJWZlaS{_v?)?cNcM_(rp{l0no)UB#Bdlh0ayKdK?MVH-|N*;$#oB-Kkj z!-?>c&@vYELmEXaB+KtlK0CHyRKwGb@%}}XOy2CfQXBU5=IXanoLDSRoRX4yI@W6Z zvDvynl44IVG>(1Pb2R|j@P+W)UlSwF?sQ}W4GJFs$)hJ8qE zJ*(`CU=f;T`>9m~ae$BRq3PP5)q8+Z&7%o-# z=LXSJq;_M^JoQ`CcXg3>dn>tP3nUxxe_pPuV4$OKDWuRhRGp!1r1Uagu%j&#`gG%OYbTRRvHoFaiDkCRFCdeq1oU}4yhYFv-F#OKS0t`j$SPC& z%AeWSI}x63H4=VXlBFPsym>(UDE&d^@j8#D#9h_QOoS}_J*ur{36Fd|D6NYQDIQg6%A z!Eh*3&pkzPq?xm~{F#Wv zSRdV)H@=ii`X7~S%sEECclA=Qhw@~Uch+M~gw{z%UR8HuzaKHxL7Ks1IO#{_{LN)!kLqRb5qG_11g*UTL2kz8(sz%nu^x zaX8;4GiZonhS2tcCG-wl*)ZRAOWPu8l91+)GBao4EgHILmkd0~E-U&Zyq@5Fv$?>) zCMVVsk~h-+GON3;YP^SJe~GNlMXQJ^aA-gI)gEO+3S=w>C8FeD9-cj^$&$_RCS3uQ`5$ zP=_#Dv7~*ubyL2veL&AMUZN0RcfZhzey#r3ezmMU_fmMAM4vf_IW+-u>el$L74)|Z z$mhyiEo)nm0<*h~)%T7M(ARN?=j>cl66sI=Ov##^SQVT7JJ&dI4>JRDe*bUs{W=b` z&2?+$ARm>_jX&g{vu69P+`Z$kQvN&GwT*!`yv}#-CF}2Lz3SuXh3^vU_ylg4`c%mp zlTcR^l5#>}o3=ms9hZ%ZiMQ~4x2q9ac*9hL)W$meb)bwon%{K(9wRZ7S?7G-Pi;pW zO|tooV`QuRnj^;h5iFH|@Uda%z{NZVTsdoTn^;m@jyb6r(%KBCwX7VL`fbiR{xHAd z&ULQF7(L=z)fk7dV7XCJW%baSU+Url?}qBCGH#6=F0eCF^RQf*nd4!Vd@e-eI+1aK ze*nFNMmQHZt(*TgE7Dfnj)_hQZbAB-T zejOufP$i6L70fG_fSnoEGMxUYQXAZ3spq|Q==B}*6Y6)Ce>Hm==&3qoZ6buNEsnYx zcINFGZp?rAWkT!CKKc?HvIiqu4Z3c>aEqp+cSB3C)DhmnYsc1q;4pzE#0o0R!d=et zlFYLn?L0^C_;Tn2hgCV-_i-dlmP!@vIbJU#*-Pa84*-XyV z#!Tok4TUxn^{EM3D{gTep4!Jl^V#N4!GSWn#gMe|QyFvIokzqMi`GDAx*Z)m}QHr*%iNd=HlkXu-|vhtQ=GsZPgdsgm2uOHD+<9 zn1B{WjO~|t;%Sf_K3N>fp!;LkWqehHG*#qz(4&X0?+xkCLDCtfkw|)DaryL}P`%Z{ z23W(pht>c3AyqhK*QCHVcKG~jWjDw@sAdT!p1 z3bRKYf;kwa2C-8S3BU^G37B32Xc{p)cg~Zo}A59anwD6}RUudE(CXRJX6u zpOn|QmNkZFIy1_+S>})@n6;#)u7<{v9XX+IwFiXE_2*?+kIHyvLX%^44r1JM77CooB-?qPIE?G(<>x zE>zrF?_08dkG9w__F-8+bYS7bc_*BgeCqZ;Yq1xLcADu;)*)rqUTyJRla@fE z53RI1yn7&8o^}stA+oDIlC+o<2_Z_p3jn% zx#eYyI`w-0F_GyTDw)3jQl=-1{(gcUnlNPov$DXsE~}W1^90yRZptTV0nwmWvcsb= zR#*+h1qMD|}JES1D`kB$AGWDjc;AlOW?rOIT6w%Ww!jVNM+`>ZbTc=JAH+F zX)TtDkpkTtB~Xhr;ohK@l8W%S`A*JtZ*$Vf`AjyrX*Ay?jQ7mjmCi$vsqLfk(R-kO!>7RA|zzbHGDELWfUP z+uIcH-s1p;$EOLqnruSG;`8n*Xed%mS!z@>vzAwDTlMYRxKuo2F?8Ad(2xpLr-|#T zSl~(!x@l?lz*_hB^)$X73|;cOas7KYWbE<`Q@o2a{ngK<{mzFg8<+7kc9Yv}n;a@= zGHh~G`q)qxb_>uWyn%Qlo!PMBedMoBo2%qt8P5Ne<6-2Ofw7S2I_^IRjhzR5)2dA4 z`1A)Lsl}c{HEhC;wERep9E86$=}Z~mRPLAOn6|h#$#YFx7Qf&(r;YLHhG$Yb(>lip zUk-FMzeL(CwY!jR>(jOJT-zyG#H_vF%S@Z{8;~P0^3*t=I>4(bwpK2(L)XU3nSMdM zArh}gNIAE9Ri^LJgC<5h)ZenXesJ=u?G+QnBembSseR*sKSVUXGGpIiFUs1V18*QG zt(G^+kKu{afxI#c;S_vZ8>3Ik8>bFyq}?j*IME|7%oj6O8O8pq;&QQqnL_bc^D>+2 zx7KffbP(Ty#k}^9^-=Y!9dSMjxCk4-L!gz80|$Y-hx7*TQr5Z!ogX_APEEzPxT7HpaAXRJ!f9bS#Pp`LrZ zRzWrCOLGC}n3S$}{2q*B!j_p0Y?-J`-~j}FcK1F*R56|Ja(h56L!Z$dMxGh2;Lgk> zYFYEU){3iBom?)TCY|Ebt||71DoyVJJLj>K3V6?80l)hsY&QEi_sMf?8{8Ywe;XDD z;KzvtnsHTxm<#x-uwFqkpYWW@4^rHJy3dJyKow30Rd~X=Q7*CZd;b;JW)5&|RB46? zu1$`DW3y47`M=O@HaJnf5jv4w4M4UzruJYxrT6X9pjZej;^1!w#_)|BEN?IwnWcN2FgyBNF5a6Z~i z6eAy%&5dvJ7q5BqR_=)jSCyF$RQ|ukMtan<4lUCM+MRBMz{%;pi6n_@qYTVT!T@>{ ztu@og2UMCGdA6zD^Nc6YLv3afer>gRL2Bh$NI8pT9m1JuOyli+@~~oOo6&tq;cVO< zGckzNQ-6S!dm^+$Yean+TKo>QxTho9)~9_@PlI=LBVUbgm%Aas!yV>2)_oIylGX!S z=O4DgTNfy%kaYe=K;acCvjgFh0zH~V?6YXqB>OC{>~imywKiu)R+H1pHV}Rd!|NN0fdg(lhfu*>ZSo{mwN#JJ)peuHTra^0KXa9r34%u_p}k>(t=a z5e-kg&hU(|L?#^@!i)Z*@l{!Eqcu6qXMAhT&iP~O*FWZ%v6HBHCt=?H(Xq2e1?fEF z>uR`>U-+@I16}D^%wZ3~tAt(P#?iXYS$4}>=Qpy^wOUq_Cks<=a1B}NtKMV&Y|r6x z$C?$9{VL~$^;{Ft$328d8{dHvB>Lfc{S9ddm1E;FiLxa+umNpvZ6s=e>=qtrasfdT zbMBOv_as|L&qK3|nLA+3536mx8nQVacmrHi&gCN0G1=(WZa8*9|IV=s(JyvM^Wftk z3zSrhM(Y_3Ix8$U$hkZ@gZ6vdG&6+`>F>cF?M6e5{D|w|`JSxj(eVGa^E~_9nlx!8 z!W#K;o8D?Pi}+6G+NNB+YYD#H?IphlZG|)Ex{?yd_12OanO}FVMtyD8lDav)3V}j5 zT7AtveT6*r`6KdVpcTw;j28@(ILJ<*VGeG{Bv2jXcY!5$NzvUO_-E&uV0qRN)Cjx4 zi&+QW$1WUh9JYp)dsd1ulZ@s+$d7;y7cn>6xt^iwvM*iX+?11IIm>rgqkmR-$h40k&ddvL^zPu~As88YJ-*8J zklV_cRhB7%sMzhUbBh_^;@?`_>Y5TT8s4hZm}+F!I>%*MT)fy?StCcamP6yA-(l$f z8qQTR>-MGpe6mK4$F^cpui!Ks6zx>A{EN0&jPa)JG30W!xt$;AoT^R=_U;(bd-D->^`I z<$DaB14xJ!+-mG%NzVNHAd^v@=8o3E|Rj)cU%~=>}A9evNkwv#Yf|xF87rZfW zV;UU(6HhqbaxoL_FZ;ve2=NHJq}P;P?#e1|g6_Ce?2=vqVmfgeIwk&-51DIliFoQ! zTdwgw7D(#6tKA5#Rl3t9{jTdLWe-Jue`U`DK;ORtTNl2$0IA>VPHk<5?rSu#C!sfan1`)yQPXV4Y_$56 zi>ra(qwc*yG;t>yKbM(X-S!QoGEFbyb02r&%r*;WuiZK;5Y9ST;5kJHM1J`MG-|lf z#!>pAXMK?2M^kNB^7OpRXJXn_9MuE57fAb`YiW+T~AsGxbKXBx;jtimGfw2itrQJ)D*pTtqZ0SEv2UBY#r z5q)mL+?odNH49w0L37opjvqlAgrp-8>!U8oeB)Q^BiJm$Mg@}Fz?p81Py#Cvwa>Z= zT$W60b=a%Se#ohH&0UiA1{2k(uoX$Y;tIaUXNg4nHD4*@@_359Ye;ACcbag-u7sRY*Z_-X}d}C<5uv|nU!{bcL{x* zs;b&OEIrTrlALIR&jFs>b?gG4c?_Q3SYR^b#bcVe*Uw(yXJny`#>#w^TgVblK*MWa zsDM^3wRV%p=gYrH`W|DW_8{8xTz^Hi)i)b8+OhI;>pXEgW@b47z^ zJ9cWM=a&yZ38-5p>Xu2oxY6*^MrqYT40sRsdB&Cv$C2dO1A3-MGptgFL3TbY+M7bM zb6^P05&Pt_47sJm=@dye{0RFQ9?lE`{|>i4BxT_1QMYhg%mTlO_zvXfjK=zbFQRlC?9p;wLi8K8X#4Wtd4t!FQ&pqX@|OP!=@ zR_%fhC2(@d-(2jz{tcRUAwx}|9yoQYrLTA1oK=Y4g?=9F42}DEu|{lx#o%m@wXD#y zRUGeuwNqi7(z0|$ZLEjX;@3XS#(eQ>pZ?-a3_;^5U&`T60@To@?35^$kZvjqgz)tfFreT?~?_(1<w=QuyTHit1`@CjL+(>6)m$Vf~ zN>8!{7D-s#WFt9?Aw?!9xpq#wG z9&U@&JJy#`mQY^jF+(~C$v*yBpctCFU6KpCG1sB(;8|mB1Vux1^gQ_z?1dF-Fh?t_ z-m?l614}RPdBMrcB_DQEZ$8)L+X0KCjIyoe8JJ~Ps!c)+&8{o%6~Y!QLxjdW^%=4t zYHwNU{BM6o8TT&5Q2VKq{4Lzwm;5^%pESKM_7$LOF%{llx_Wqag+clvpD zui`Ryqg^259MSBh`CZ+CS$Fh8crD=44NbWseF>jI(_kfft*3CaZUgYn*1c!u_uV_I z9J~!^*kcw;ih;G!KqvPqJ?Eot(b=Qmiwi0Z3w(@rAdLfqDJWeJ@xoLOw+_BBox8+M z_=0!IKjC|O1ir{4L%a#1z~vHS?(Ru zTs};m;ZW)((T+CaG$c=%;AK{L{?C}K~mD<Y#S1ZS;3|H@)UVdPB{7{yZS< z5p6>|#ewk4i1|3EPU_vlzsqf=*>4nPlBgEa(QIB7_IJ;zj$BZeHlwFn!8ahvhJ5wF z-WB;Yir2?-_&R}ZC}P7t%BEs{-leoo9s0NqIgdb(C+m;~t4cWUX5@`VUg%t-yd6#R z#SKWg0VzLFo(1#AT?CUU)|G!l&+L&)c(yK^8GZzcw?&roQz^1IOI&hZm zKsI)ORu(l@0k4N8b5?F0w@bS*Ok1dOG1~)W%-przp=-gs=_rBC`gA8D#FJTs@8U>~IKBcrzz@MKgqOlFhmZD3bf~LqOk$IABu6)Aq@2U7JQ44!JOeU5d zeK!6%{<$sCMu?u+Ax#9|44T@@jEA)F8rC6YcdM)>4{xz7vxt3`UGZC&h5eP1AAl@a zcdLb2jl9TPxRm&1CP6*1OPV1Q-nkXtJy^;$1v5R+(B}c*Cr?%lP8azhRxzQ`>MU^v z4)qr6JsV`>;a<<%i#EDBdc3k9==fJ#pfmPItf_g}pB%gY>=}B#bxHkX|DB8+3U(q>;hxp0?E_ zi&JIjyzh!DfGNO(XKG-&)>I*<-0ECWUIKJ!W~y^$VP51gFVgd}8twx2`FR4NKA$T)mr2AoaTtff$V{OXwsgH?^^-YK$ z*y#;ZFh{WlX`y8p1iwOAS8eERQx`@#OC3#Gcz58P@wNHaLzM~OR%?9W@+$%_vaCaV zElG@dcetjpXAF27tj7yhIC_9Pp3FL=09GGxNauD)4H18Y%=Cjl8CLyN%d_A$c+n0t zYKev+pHM-myZh#PPjW}X)s^whp=NjBIAzqvtD{b4z|U0dw_&NCEX~0B32FV%D`&ZT z>3dxtO0K`?AL_p3hg>QN^hwL0wEm}L$%eYA!FMl%Z3~78AFj1AIX>%Cuoe zOR_4OZ9AyG*l&e?)-{M8{Um1I6TEyy73{;<2512+Dazs2(Vpm1#5x+fla8Liw(SW& z5mbk@il2-a%nz@2C*zLVY+Zw$Pz?~E;9&QaF3x-&a-9J(k88w?x7HBmB#jXopBjui zc+*-=tM6fqK=N>Ra~!&$)pqAz>yUoJ?Eg#sc8_Yg0bXB58H3Whig!WU%ZNIiYWNFx^Bu7@Bekklq=iir0yCDN;y-o1l!BX$>vh=&XEN#rc(TvIwWAL3^ z2o9Rajb7x86^~;5PQvapDD~8I4zF*c7Qmtai^p2nE_&2;~VjPCjJcT zmKY)6uN76f;j`FDH!_!9QYw(Dcra%POI1l)FW&v&eEuF z<%O1OPEX~1$9o;(AXt~&ebW>5|G^{vPM(YLaJ?Q@iteB^qnmtq(D=xbjqNc#)q>VX zd{LsdiKY##cmcYHRO8ML*4vtJHbwu8IA)Z&H&jagLlI;1YePtiT_(|aXf2c3rXf-=|KLB^$pT((16 z-)XaxB#T?O-NWsYrQY4d1DByyHxQnjGMp>m;Y<6pESf*)BRzma`?3Yi3I~E5f3`MopC=088jGJpsmwNdeM`JhjJEcmlm8~UsnOj zZ|;Ot#mKCK((2~+I+caKIC#Si8Ov-Z8+O!tZXq;>7L_{>`?U%u;^QvbeMD=4ZV9~N zUzGXoetdK6>n-Ey+k0mf?AX9NcnBV*fTQv=?2%wG(VEOGx``#lJxx1{W$Eu7I%`jp zwV2jDN%~DwXqt{4eKG8-HZRUprT4t&V7{zF+~`i}CHcDlrcO6_Ci@AmiF5(nptfQK zb0c{-kf#KtF$a4$2Bp6R<62ei{dr(G#LUcNm+Rd-+Vz^C^i&Yi`EB3i8BVE>&jj^u zM~l2Ak46}j)+khh{PM%#ylC2@pa{uv)TU+e&AI|{auXZ!kR0VYqSHa=Z$^_|gjRj- zth~i1_B(dtj{f*2$F$>hZ7hZtG8<cr(x^6GRSpeY@EM%tRKAVJc^@j@_L)CN(R_{1aX6d(^rWs%v(ipALE;ME ze^vZ&q(IM=fa5X}F*(3zdCVW!XAon+Q|vLIO#DhW;AGsR-(FDlPt9!vveGZ&G3P*W zb6n!1@5iU)zB+XhuzqsItwn0Qe_~Fq(-eO z6O>}Rqm*=nY({Z&7!x}3nO+fvP@E;4h1M59md4zuE zCc*v;7;Wbsd+!}QNKRyMMYG?PKSd$#M+ zU!J||k}r*QvVl zdAo@-0r|?%sp`sxSGkS$DHjt9%!W^c^7TQTYb1T}u5-AbqYdiXH#?$FC${mtwmoEX z2L@GdcGxc`R;%tS$(w~Gb8}T$ z_KRBkj|pt>K+j3L!kf$)i8Uec!fHpx!l+w>wYVbQY!B;Qg!?- ztWgKtdf|<>Shf8kZ{OzsqTQt1Yqxajx+cR5o~cuJmFv`ANzCb>mYm3N?g@4P&5>#n z6^v7Apby5P2C7c&TR) z>F5Q=*XGSXt;#CSwO`cRw+B@lceKTFI~-pMZwU{dnC^Ydvlo<6G464lI>~~1wA%;e zpsg0O!QpmA-}9&J)bnQe{(HsF<=kwsz2P<(8)L}1sLesi*I#p}J5^VyC3qgCXN@@i znqwGBFUj4SunK)IUDpNg%EU;?)&^s*td6uUMoQLQ$5%W0o>tvgocmS0aFGdF{^8&z zX@FLC?w{b5|Fbafo#TydD*fCxLoAn7=NEuwXc9JJCG+{c!n1zW_~P7Aewz^Gr?KPk z(>N#XUeGBf-DFuZhwz=3SWLkG8ZArl(1WD2Kg*{^W4{JGOX$0rSYUmJ7AU9BxLU-b z97c8Hl01Qd8U8c3_ecb;8EXCo882{n;GT<}z1kyE2b^whKva4h|pQa0b z%OKk}Dp!`ku4$I5MqFbL0#6`A!*{Q`l{=_0>cLou(>I{5P6ltcQv#eb{Cxc8sfoSuoQlNB}UuZFsQaj z{M0e|_4h4?hK{(?RqLM%z?&?Pa4^CjUvOb1D$V%&G!eiX~0rCQFQ(aj96TeRNNK+dX|l zv`>qB*Sp=I)~K~VtEV)V50U(f@(~{4iYxkBV}3VityT-Qt_ujdwG*(OJ&<$N1w7;0 z35k}B!o&tA-vH!2o|NWzLY>nH4rIiR!g zw~#&zlc|)!a&%#jNkj3~#N(-hWR*F#AP76iFz2^i?ve(`vfqAv|7dRTQ9rY@A{x*1 ze!4xnJ=-~z{tX_n$RUPOGGq8u7oroeK0Q8BgSN#s!_X$mz3h9c?Ygd$&G^@R%TJo=RJGTR$`NNeUHMk- zi99|0h-?P>Y1Aq18tVlV)YF=RYVj3EEo^7Q-v(F{mofYW+E z%>mKJ*)=z_gZ|qP;>+CPkMXQ6*JzBi7p2lS^f*q)5zwn_H>tQP&K63G1H#tx4xoz& zdX(D(oHn_kXDXgFPYq-mLHMnLdO9EV=$0xV<(sI~qBf+%o+4jCAO~N}I!>T=SQu&( zr(AW-F__QArwR!w{%UJUNSXuf6N)Fk&TIuou?!q?+X2X&(Ry_E!H^Y}Pn3_YCMjti zRNixPx8VSB;?qOtJ=$w*48Yp$?=g^SOJ4xEJgGr|x$L@YmdZw%~lfyIbmjWU91z<~oEug34;ZP8-hft5OFG2%CBSIrW1H!%t^$6n-su3pIZa#;ee5_l4phS#8o7r!uX(j@PObmq33o%GwRTJ`DHyU^GHsh)?C6&_iOrf z-J`@uP}41rOkX9=5^*-%SC6weoTd3Lm=Aq^LjSZT~^nMcTl2RGrxvC0FV3qze=^X%vgaKvPWYISe zx4yW`1Y7tpPh;RD6TFoe8)k^x94X$D^Xu?FoHZ3v6zF?hd0yS8@!kXd3cYi-18WA`@nUDROmv2vnoGc{$H8d5gE#7A|WLubXu+Cb6Cf>|^8AvcXw_PQh=)5>_>@@_Jv%*)B^OsNeCqCD3r8S)Tr94fJFoc3 z1xtsQu!(aQl$vG~FDYjsOk?36@klwG62DY)TeuC^l)@W{KNY$DG7`?Is93t7qIhm; z<>L#B%NDV0m&;LEw&;n6T&%2e@dzA`Ke?#1%2isjv~+ISl1dbR@1lxD#S2UCV^rSJ z0l+wkgnT5_BH|s~*WsE%J+9wG7#)d^!ZqcKiCh~ZVUI|-q_nc6V$ry9ro3s>rc4`W z%3e@eT0Hk@6K*b2>JiN%Nlep9pD0_hw3KRW%E`?ck)88^32|k`3ruq>%bqH&{55Ih zVM1})g3`IBr4^%>#BuYNs45yUxAdtIOP4-9y^4iy-bSeO*KOCz>4kKrug+ll z#}H=Ic^cDyn+pF#IMQ(b7u*|zZ~~4eBgdg(u-6#Q^rbk?;&>8AH4b{FJP~i*F^~PQ-3Ze5HH2M&_Ym!(D!tE)8nE~P9FNU!m z2wR^R!(tJ#s0pkm!m>s4*rMV^EOik&I}LrK;DU|J3FCxyIT%})^yh8LT~TsN{G5BA)9~RPU%?f-f(DN9uC>W zNZ8lDWi$O6?|-)M2l?MWQ*-~YoW!;t#>U@2ZjJ4SwNK~WcW~9IKh+=Kc5mj}yS}wv zpLoxNx3A{j==tWTSO2u;uli4BrQ}q+H#b%LB{e;M$#x}RkA}nABT88F_djKa-!nU> z{~}F8!~PAzwT}BQ@KdrL7&Xw=QLya!nfEp=S$=j(zbB^_jdo0aYUJ>dV}{$F7(4Qw zv7<7_j2xAzjDev{8P(Ks;bQRbdkkY0$ITn3Bj*#GO#jO~rvL7@7@x)A_|0>HyA(OU z`F-G{PMM1VIiQ^BADPee{T4EPPlRL2fZ2rOuOf7Gah${PIBc)ZR)n7w13M2YGcOWy zh@)#i(m9@7P|gY}7Cb$tvV!4-OpeK>$fc>Uxctebr3H7h-WYc(^zxjMQyBp0Rd58p zcNx>uLC>j+gegl#q%1-G-mhl*iEgHUVR<i+OAd{J=s ztkKVnd8~?(D)hYy{}}9h29Jx{)Av$nIj6+@|NIT*wi#~DBSorQ$Zgg@pA0$gIJe+q zR^Ercv%Bf>u|sqWet5HcSpdUfy^#y(Y9G*e-plc=Kwm-UWBN{&Pi=)XQ@@tJ$ k{xQVgk9$)QH$QStQA)IlO~dJ}{K`Eu-81Tyn{LMb2dn$9T>t<8 literal 0 HcmV?d00001 diff --git a/boards/holybro/kakuteh7dualimu/extras/holybro_kakuteh7dualimu_bootloader.bin b/boards/holybro/kakuteh7dualimu/extras/holybro_kakuteh7dualimu_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..ca38b363467fe6395832862205aefbc383950e4e GIT binary patch literal 41844 zcmeFZdwi6|^*=t(WiQDFvbms35@0V0CRu_D0S)41vm2g-EEq1@259R-&^{p+BA}vD z*bvkRS}9SB#0x^LSgf#tSR=+nK&!QWzPmu$K%hioT}V)8NnoE`_xGM%Vq0r}-{0@Q z?;qcNy=G^g=b6iyGiT16bLPxUG>~+aK(uf2|2Oa{1LWE-eCf#cpZ-$y(YHM+ z&v+`v^S*C;Vyd2zR!DqM=D+Pps2)%C@o~*LU+cGQJCJj6u%ui%r)2sFUDw!!9Ep{6#AJ^>Z(bjl+Vrr^;5^5?7iAd754dY$oi%zF~I6g7OOa=Z$M@=&^6BD7Y z4~})E{KuE;W)oUHK!E{5G)6bwV+un|mvlnQ1)lpjtp+NI#*Z;a$fv2esol?Vr!R zo@LQzl%bW#&%U$##(#M>rr%k7RLP9|+tTMEotMsEAybbk_H-AXCLupbchJ2Hjv{91 zZQMXBixUvv28c-dcEaAoWjd%DEyQI4%1lSE-GSC3>22abYc6t%nZHKrgwmT{LJ#CS zD39E|>3+1~05(62v}MTLjyyTVW>bRugrWze8bB@}C(@`xpU%@f-jLnrKcU=(e%lu~ zdI?~=3$T^4=hb*#eH7^v$~=Y_hojen@AF2U&3K*~eMWwY@05LK`6KluqI}}N)Q7y+ z>Y{e!o0oo5fHV_3Ut08mi6k10cz*%$CB&ByQ^XYUmx#Ya+>5w(n!YL82jU^~fBx-o z7a?J;vM_wfb_nxrGqHHg-}dOMSHH6fGpM>pU&AQ-dY54~Mmtki!}od~T<7I->*{r$ z2fd$piG_XtvVJpiAN7hx+xvu;yt~B9&HOr`t0C5Jd|DTtAJn=ATUKCsJaG$X0~4;dBD+{4-pfS=o;%eQO{<0IP}}^%Gw&P z!JiQ={rI)gf^6yHxX$`mC+}uuY)zXE5c90dOP3zF^5{lg8!_9j?&g+fCLk4?X}~`@ z9GQ39xw@?m{_L(Rk5*m`U>4?bwO0aMgnv~_XNrYZivSb!NIgs2) zER$rb+bC6HEX4@klB=Cm6smiYYoc6g8aNZ1h11YR4ce&0EUL+2b;oDw8*3hKoP zleA}qpxY^2S?bieIm;e7GgA8N-};k@uGa z8}W4AoXW^kci{O+FGLYyJ^K@=qW^&uP3xuj;;*zfY;!D8q{t_tZCApvC z-(&eWpmnj9j|56+*!Guz_yy_EBE%u+5z@a#+(9~6pG>n^9(}_SS)lR4;xr+cXIYwC zNAeX>_o8FK&+?3&jkz|ignFic|BM3%L@%OQUBCMnVttqaO2dCG9o~-RN}E4(Ac1sfAI_vUk|r@c=F?Ut01d>0r43I)-SQ z5Rw`^7Vh`uk|>2kbHm2Q_(^9kk}3Szv2Ol=z9~gEcX51*TL~mJkni%%_70vnLT0w6 z-FrcqunS>#Fq6;B4xK)yy!1s$*LL0CFX-reMVx6znAqXHU?95?Oi1M+l}FN$T8Gp+ zay?QCQVL0ADGn)a6iW$630juYAf*vlDjuo$rVDfej}?VvgJCy~K*-(l-=CuW{{Pdz z%GgTmUJaKm-kF?mUJZ-+}ksuprmWetowQ<%qr=+PWpMz1gWI!`a-#9 zLSadlp{TrPLQzTA*x4(3Cd@ABN-3`BnNVEPmFl{`XM&5tU(%H}2X%fH#o6blS%1Xr z-?TG)jkLw$-9eFmFEG--|F_W)v%^={?PulLxB*tnNIlVU6#1_MSlVKV)`p;M;OM~t z4)X*wVbnGdN)+~AH9)cpe0s{o3(_q9jV zQ_&iD@7PM(^maF|(cbc>i{#_ZfRNqVMgv^-pZsGhv6^HL_$vz$Q|-INh}fi+I4Zs; z(lhUKMI0@8k2GuJc*1z$t#dfbt#h9?i@{2@wX(W_n2eacFNOt+!F=;<%fmM5X4lOn z$1bXJ)t1g`fgT>3KHDhW?iT2W1Gz5lO~d zmCzPNO}`jSbLqT<+6Gb)YiM78O5}NMn4>TBanv&)(m#hqOH2_fVHi+FO3qN!k$Att z(VW4-K(4%m)MM`JG523W(7!^orcoGEq}vcqBJ4u=Ey7-eDal0pSvApqn#On=_(f=O zSmm-`eblksM4l4?Z@XfY7;huZzkZ%**MSGId@2|C`?BF{dCq^AXZC2KtwEmGGb7r zfb;cCZ9`mJOz{H6W?SOryIc4L@{U5aD@8_dYnzB!<+>V3kysg)f26Ohyq3ufKfqUS z0$&Y>YKCh8ugaAwTfM5{L^-iB5>GO-+G-4SGivKJuVjL$lXkOxNyvC3ZK|mBdMfcOH%;dStWB9p*#A-@wc>RN@^;o2|bCY zxb`Q#3#1uRCT5|xUmUN(S3)1cm!#7__OkTuK2yh3X?`R}8{U6&dS3;x27OZ^Z=C&? z0=l}{Qfx8uzCdV_B91@b9=9_eUkQB)PwkN!AL(P%i2goFn#U#)ZO+9|i71Vhxa}`W z7?mggbM-u@^zK6NoL0y@Vr)~0jhlW`ae`dq7}c(qTL@2w!c&V?63KMO>0_jP$zZOu3AAj$EPkxF|lt3wJ`@J@wOH$#dg4c+khx}3-Tpy+B`g^ z4BS=l*{oDQF%~Og++n$0{+T=4Bl~4;?A=N_A(=iOcauO(1CLdx3tn+tcbuCxXI9X^ zimJ)QfJ+fe?pDMJ;Nic9+&AEnxEGC*HppoOda1vlzz3RMOj;RbljDJ(fT!t4^nmZ_ zF&w?CFFNn^O?eGTt~9xGt3U;TxAHzCC}|J4FJ}Z)3GMP?d4XcIxf(mSzFr>9qxC09 zdkeu6202@e<6A#xR013*P@t`f5}mUWF>4#XtQTA+$$IqViFo=} zF?#m^2SP-mW-t!~DjR^$-d|Pn^y6Vs+6F$qZ$LF(#2n`7ABHm_%Wwqx%78 zhCtuw>xs-{8t`4@r>3|$^WxQ&g?SB|WtB9|TlOet6;E+9%T^Q1K6hRd>su{g!TQn1 zYEsj0Kyw1!!{!TJKinN4blYJ#kojEs?5z4?7AW%+ZD^asE)R$BFW1zaSv94aOkZtYc+qE81t}h zFq&kvs5D$Jjdd}NXPg`kNkj48iu-4}PqLP(i8;bgH?4k$>4Te~k@Axhe8S{pA2&JK zzv6zA9P1?ME0(uMG(tiXpgm6?GD=F5NnUY3le)hRnB}j5u`%K$tO0C1u6Nzsz*jEJddO?2mI43cfZqs>6!3el!B31YmEY<$KeELU;}?PkuE@*N z4dJirnZ|0A*odXe-vqS4Q+c>2pl=W!tB$TK-=pZ!vtbVjkI*!4jq{_uAJE`cv%3PE z^=p6A1-+f8)xf(U7Bq>Fhn1L1XT9PfK^PmkX~sz*Xj0*63=THpBsfRKzNUxgHHyKz zBI)tryhh}idhB8X8%26x5HceD!ypYrOXwrHbm7cK1M1rfY?Qigk2GZ^lfHDgbClGpG^jYI1{Ue7EXx!!Df zv3rHQ)7=qBm1*EdSf2;HcNg(=->|XqF2rvPlg#5jtL$`F$kp!1i2etJB1ZA+dY(Qo z%*OC=;D`HRFS?368;2v1X14nEMxGuUB$<1B(6iTk4%~b?khN|Xc*my$YN_;~Q+6FB zv~_@FmipG9{d#$myGO25izlPl9KNT&MyX*XZXDycY*bkVzX(~G(Byv0MvYbFx31G#c|Uve zNuNz(QU|!3`p*I7H0GW93g#V?l}709j|Rr4$>iu996AQ|V;c5@{nQeS6`Xs1o0ev+__Q}=nYynhHVq_0NCNjYOcTaz{B5sfM zF=%=E$`Ds4xcR!W&6>zMs@lQR4~EoO)4%bZ-#S}j7Q^$^JbiBHq*8F8L3VYiRQE1t zW!K2+U>qmzv^}4b6i$Gdc> zg{NzVSWV&3pN5#_CT(C3^m-NK#We7q6O5ZveP6WiXWnCcN!!4?IAbcl-qja<_Q*!e zkHI05d9oRnMQHQH5>u>iNK|s|eD_gqvqSV3t!r@-$^mm+uFe|7+SCVp%UBEZ8a#3_ z4-4Pwrs#ec`{r==t#<%FSqg`_KsA zinfW-b3P%1zsxP6e2np?UDD$RY#7TIhAQMW-W%6(ZxZw8O5C^1yfXVdXO9GQPtNxSo z#}?~lx0hH)x5q%A;BHB=&x34c@E(zOIt&=!&mwCWbXJTYTNl~-$av}x<6qb)&J?V= zHbU?17cCmh$Fj|Yy85FlNnVo%dmQ{=2rCH6|G>IH=x2i?tB1`i)TD~sNpK<$({GrT zRavNS2!}3*A+w)e?%=61AiAS#gT4th{(z-c0B2D9x%+iBTy82X#Ka;jk4gbdK8ZkK zj>rvI4H?x$R`ZRj>=?i5{_GlVYGQr1hnVv>^Wf;eyarny@Towr%yebl={6p{ND4At z?Ei*q{~sgGo_RXHUnLcJNzkpC^kAlBm_7wGwRd2@Bjk5u)Z_a_sg!+H@i$z5=M4`U zCBrn9<2M6uA%`6~hWny9>?(4D{>~fL7$toq#}fmuU(50JcRBbQwEvRh!AKoS6Ko{u znFz3#e8=nl8}^0SY_63Ku(`%`XjYbSzU!sCizj40&i06QF+KUTqTME*V&f5+6VIM% z%#w;gqkmM?Qn>Ls?+r3{<5d4GQkFCiGeAA8k)Az#yVoYg1oa$Grw-Wgwkb>?l@QEj z9qbZ+_k}}ez)?>7PXwZ+J{z)uOK@h`Q!KpYu=_+{vUiO<(|u5W3@gsn0N&sCf%}sH zF-P;C82U@#E5<{%GVV+)|IQgF7Twdob%3X_SjD!YcjuIv13&XJcx=-2wLJZM|HJMw z`Jj7`+~ckf%me20p;NR(q&?JB6XoeONRi+?-X<-Ql5hI_B5&d8hyDCcq3#7ouRkj7 z0fK67Cy&*D$ybasGm0vO&d1Zw`uRGw6wTLsP3~hjCYGBUHpv`YK_36Urv6;{q{is% z;dU??(DVqmmxpGOE?py(!lRkE`FoFVWBcr&m;gtKY=F9<_G(xZ_vs7`X%19_0Kuf#}~^j z7s=Eujiqj_Thoz>F)D^;Wo~r3KfFi?2Tts8>)l1rwfX{jcd5G{t8e(y%?*ijC&`l{ zW3;HBGqQ1x2gD2eq5CD3OC?w1D*pgmz%vSO=bjg6=MV>NY_>y#Jo)`!1=NUd!`giw zG-XG>_Q6K<0R@-Zrg45diQC|!C2p&+VryjK^A-BO!PkC0NMCLq_L+A+)>9u3UjMp5zLT&^P z@Ep8iN8EtebEBOe^tAL4SZzKHbFixYko?PM+39Xia&KkHu^!>}WS>P-LgQmx&2I#? z!b~aMXf)Q5d5WqfreEkA-7oY^>WYbTcEt(K`6XS2ae}2)A=`v3p+BxCt4oMk)g=%P zX=hiAV0EwaiM{q*Kyt@}zCBmSj8j1(IJ;wnC8QPWJu5@HVq#d{ZubYUnI!omt;deE zUP9AHmr&#AI`T6`wJjE{qYdFsMP=iH;oCn5a`B_u(87K1Tp_C@-#b_At7iFrcg0hV zcGOaLjC!A}?vK05@)5u#brE$5q@uUoq+dfTa8tvMCje;FRp$Kgs!<(p{K#a_?#G4id1k?P$6sZI|R%G$s)%%HZ zzcE`rzB0wlWO=Ks4c<>qtwcJX&^O*?bu#-T<5AFaE8<`UOpxjtnV!F7cyHO>iUVG5 z?1eHD)o?K>(@&|wTJHaonA$CrNtfH@mZC)+`QRr&}-pI1({Mh)rd<|KfXBn?gua; z0`>+gAzK|8=V@S`7Ml(vNo4;cjWfnIIx?GQNYSw~p?pGts(35(4DHQLlBbC)2nMht zV`VxW!zbgZc?~4vLs^t&-S_x?AKkaK(Ew_-U;f6j>+(0ovNB+YG+oF8l%F;`D^8kQ zDzc=LGYthD_YH?S`#UR^R-9j{D@byem7iZ}f!D+lWwQ-(#p=$L*t0gSqSx`AD|arV zX7>D-d7Ud4Ltc;aRDFYEr6}p7{>D_u)0-S={**Z;IiZoQx`x8nf+xw5i({vpG#lN+ zp%+0tLhvN^U=xci@=;~8(PLf=d6xMm)L^a1zwe~^!LjPdy=i5wytIc1wQi=x{IKK@4t?>RwaZrtx~FgP@e6`=(XR?^^*Bn&IeGw zR$1hJQ#SS59~kfb*{adr{9exkZ@SISx|J>UDQ;$mp-o4694h9=l#jL(#l*O5XG?(3 z(l(>+Wq%4BMBCmg9jovR{~So2&BGVN-yW^lxpLl$gUSMP8g ztoJS)zu2)je<5E2pP1)>&m`w_$|9q)t18Lab!3f`+JtKN7ry}if&_m)kR)9Sm=D&% z1H#7JvM2b7l{>v`)oE`MN?+$o>LnZFnt2On*{uA?RxKax@g!|lN|9=h->fXMarE_Y z$Gw^0`hnrUp|0-8I`v2BhsP?OQ`}@I^m3S(St=o-GY^Nd-eYt7qYCxxZ0UKt9}XFz zMHw1ddMLCrBKekQGr25T+P?Bcd0qVu^>390wxrfWpy;R6@vY3#ynFZ%-leG3?5!BliH*>qBz;qLMI9tR1^L{dB;%3j37(1PLJD~T~l zc2WXQt5HG{yj6ay%p;qXyKET8B4WQ#z?TXigmWvgdwi@yh25OH^q|HkJZ2sA_J8%H zGD=rLHL8gHuN#n$0^}-xtQ1!S=uJbRSB7@4Op+~;R#-32M|yD%y)by2E-)^C>TuVc0jIR z)EO&r<*>baUFE`3q0zaNSX@iXHW)V??P*aN8#`pO-raLlD0}ELSVM}db`+LvxHs~g z*K{*h!4^4I@^}ULkn%G<`L#)USr&uiguR6%Q#fr|?*#TNYnfENii+fFfHsI5ZatVJ zE$5O;{;_DXIOgQrLgJl8&9kWI-pTe{CurS?U3t#QeA#-5vva<4!x4{#mIz~=`490M zIIQcSl&O9tt*F*+aekbN%~^GQ{go z?hz8^I6VofzT&W6&|rAGAbbSR1*6tPSUe zEj8`xPuHxywbrAaD)Q~__oq6iO5aXU9y zs8(=36x}O?*4KK~*3oU8=|y{%eTMf}kkvUM z<>X5em#cxDC93rSHyv5hw}H5R;p!Ae(3jDrR()ANw3hL@G?U9|_PTQo1+{NZ|?^XS^B1&7(Scz9uIwJklP zz;ziug!M~%@&#cn>(#aTzGrXO7Wou0FW+mSywHMFv@Vw4i8oA!VD&H$jhh>>OJ?Ng zOxRcqUIVOiL!pzyj0-S%h|Q?~ly!ymr_~9qx;c>C^V&6WttS<+RArn6EMd)49YcE@ z4Je39uhx(F53u$s8(bThZDolj?xeYVaie8JO3@N-Y-v6vOUKSD+pw%>6R5wk$zL-T zGHp0?A9l$)YZC8VJU*eoyumxr6I{T#oZA)=>b47@s1Kd7vuo#DHZ0*5mpZ8ESd2QD zKVI2GmJP&u+F!9=ZC=)+Nvc?TGD5R@jJ@8XDo$FeawU|1s)jr{v)?ZmheF=N3_klP zf!L{$sEXAt{nCW;r~W0!uESBBu{>C3Fpoz`POo!AJNPTv;DNMvK5QvZ#g0oj^m(`s z79Q3E)o?GyJwj>!VTD*le-T+9+al{3kk=3F>$YO%0k5yy8slMJ#)GuXPd^y_*y)?4QpBhb}`jT^FOb7suv zyiInaWa;7sHm4aB;m`|VW*20V=?{;18Z;O&4}4%9=K`qE-ErEq2y2gW@ARheLNq_DGrnY>sN#+{bt@ zKBHy4CUesP^;uXoXN$S9@(u^Ly+7ikP4rs34Qsw`PRh8{louW3j1BVn(H>0(uZXwu zitrPpXCajF3jY&c;ciWmE;8CjIohDwFrnlZT=yb@66f}VAJ^P9ep?&B(J%82)af6Bqs^uJ)vuBakp9q|2OTSj#)g0k#Sg9=3;}oWX z0-f9Sd*%xpV8IcDAl_Z!ESnts8QR39|F6J&#c1bjY3?flJ?rPSzA6o)$~Bl9KW)@) zuwm>OMU!QWqVJ8&3Z<#LCbiK8`nC(Mhq9mQuG#6(o>;n}NUb^v+qtRff`XOm^Y`mg zmVx%+g~~5`h(G&P%`1+?v*RVxhBQ|(ccS!iT3!9Y?%nYTr^gm^mgCAa?N-dBBg(YA z{|Q|3XFqaWbD?$F2IjZE?4izp^{J^+7S^J%1>w-o!~dLHmd3}{t0FV&v9;Ex#us$g zyi0XZfdlEW1Hc7GdU`^)hJd+Fe3 zPr*-04gYz)6+Y8e#t)7n2FHx>I&6KpnJ($Jg+p9eG?%SsoS|$j(^)WgaW)|V^YxqN zX~o3IY(d9Ct5fGh^&%1U*)!B38?gGCq;~i@4O=GNnNvbCV3&_Ap=mLlYb_7P45*51 z(w|^IW|WP1H#a>Tx;V5$dBmm;9wQNYr*j13&1pB);9WS>j&HY3(d1b0wg#!Q{xL4L z!%IwKikK%q)}2In(`M?-@Knx3&*0lnGR?ii%h0n-yVL_QgeW7Jj*)Nl*J6`1z zgJZz6!lA-}B^_}$PHc<6td0ALaswsJF*gzIhX`X?xH%gC5wR*S8b%?`LO47<8a5)I zaebjiY~{0g{{%H@oe0}?R7%U~5acE(d-!(`p9(Oz_qLMk-}xDw zy!CoNnY^+0f&GAos59@ldjI~G?iMl{l9z`78XLx=(g+@LGyGj3{||$UTQ~MD+RvfX zkM;}FvK}$XvX%yJSierQ@yh!BBzt4;Bm1LuC!+4#{Lz|cw6S{8)9=-LV)%Gq$zg7? z;4h?l%?)cm3-FUI{?F=lhht**tmkHkSr=BoiEzx+a>2U; z{=knzPbB^4)r(rIT;o=#VE=9ms^b^5sd{N*eZ;Q*Mpb>puI@$bxp9{Nqn_9?Bq!f@ zPHC%3o2VX$dE&3ivmRfn}6g=a}fGS71oHsYy0HS0zWdt*>(1t;zs+U*qU3M8b?4e3-_PZaIJbd z!M#LloO&g2P67UI*bB}@HTKp57wq~eixokS5zFKt1)b7xwc}ek^KGtTMKG>dPi`#m z^OW-L>?D7yGR?H&@bk)Trl0q0;vYxM(uq{$RPcS;Jh%e-fF^OpTCQ#<_I7ylq(~iH zU8+Xcx?(-6#RwjhfmLDgkk*_L`TCGn6XZ17V4C(F|KL|MBqP4Qt+0B>&t|Q>hB?hz z3Ww7B{}jMJF3)HGkH1aP>#^SH@*8ynnk9Akz7%=4B5nz=H+D!O;m{U^eaV-!MP@2S zzGBVo-ydkxkk%+Z{`%F3jK|g`qW2Ic=dpFEvIG`>?HfUNELV40v!<0Zox-|zN|{z# z(p8ko^=o^q4!%})8JLF0FHr>db@uDP%Z1vRKE94KXLJcFx9d~ncL9$(l?3CvppqX) za5*nq?=PMGT4b##9N4KmVqB=vV72N*I>9Idhg%TuL?3I^$*uETCRng`Dv3s%qtgNd zqnYiD&`M(O8m&KycUzEi3%*YU*0pA*i?!IJ*0j!u>^WxjKvEgqpt_QdG+n6 zRK!jw66*b|bRjH~%A3lIhFg zkaZxs`#E|pbQw8IT7p`mdRA1k9?AJ2WXQqLr6FQs_>&c_bkWVUZdi1#wPBrmL1y-< zPr^T}`w){EBj8dVG{#9;s|Q0L4?So!;q1gv=x$}4D{N#E+tqrUfQmuT;bbS`OvFWq zixA6*WyCdzYY^{6ych8&h(FQ62IYoi2YD|UVH!djf*~^;dJi6zdzFgy%dwhOtY!Tf zftlfTYq8RBT#3uGP_hPc+L|Lsv*$(JKbdete?2#~TKS27Dc#6vva6LMefc`JS5aQMM=7rC^b?ESbh@6)ZBf#frr9*s79}~~ zqZmydCC;=<8J$4=#Jqeq8}UDencXU?wcOV1p5w8&=k9TL!s2HaI^6_AHy73;V?s_OFfn$3_12 zk^kh#zhTO7=t6in^w%&b0QvN#VVpNjF1@k%80PjdterVHX_{7Qkd3({^DX!pl~CBS z6l0uI(f`D$7}9DT)SuykZ@)2Pb{fky3Au1mS6hHwbC7Eia>Z>$E`uw%Xy;N!X^Y*9 z%2SF>bYs4$7gM!&eZGl?Ir!q57B3xBymM)lc_(&VdWXZIoqZ2t_f)YDhN|9&jE?iO zy0^3>4k7mK7&7lwqGfYz8sY~aw=$Yywv7%ZSFiwn+<_1~ctFwT#gUQIn`Aqwt9EcF z{&`kYI7M(ulhj_mcH*)(06V876tNRZ3ltt_aNs@Hya9I51Mwsso^}yG?LWa6;$NRr zv2XgX&z0Anp%;TfuY>2!Vnr34K$gn;#%eQ+(E7NEOp?QiO3mrigaZ97$1ZZ$+kx5F zXV>^aTa@Uo681kmsF?-6;~QzK27j?RR)b$?RVVR#&+X#!VSR7)Z?t~m0@)^(Qhsv^jhS7jy-bL ziSu%;TjxD5pLSd1($x6OxKoybrDNUm=ejf8BmJ;Ri{0>l50}Z>$O&|Y3s!SF_G*-- z3|I|p(j+|33BM0)e;!Da{wLzu6b`)_W_DM$S3MXqz?+i!-LaYTOuyEfY{Sec8Vnr5 zyn*%0t&@`)weYN|EOf~R_|?EGN80N3c&p)8og&A&i{Z~010L)`4y%`W1=TwG{qWU% zx3UoQ3olMyPI2>%i`}fY%EDNgyWZS$t=?T(Z+0i!)f! zb`5Tv=dw5fiQrCZWd1&th0G7Avd{;gps9^IcWz@bYKMnVZe?MTI}})qFbeZmlvuAO z_p{SQy9x(GuMXI}korr6HVbZIjF$N4``Ukd4}2I6sCPov%gsdo z1l)mx-G=#O#vj6ItbGd=5qCxibVZokX_Dr_NA*#Koqp2WvDbq+BuaVAcU*xqGmcCo z)Pj^4oJR;9A4$E0)K~>~2F%NVg&SVmiVfVNK`F4+X@rwDDMwaILF~CPo}z+{=gR3T z0X23XVF3XTiI<4=_Vxpj+_%7o>wV>Z(CIhjha8#+7s4F`$rZAebu6W5Y(SK9w zRLLaC*tsl*$NQ+$&npsa0KD)xVw^u47Uks**47`DF9Tx1O)2qSGWj28D#|AobT2*R zIO*#yU!2ypG+E)SDV0|PB>h5Q71fIW6R2!>0-oa6!3NIGXs~{;-mF#F={WZMlRg#f z--K=jUsPikOxrLNdJde9t@v8l+kW+d7G4{i8NR}%Nq|ITYv^>Gg9+Nmz3^O^l}qTY ziWpo^jwzmbgx-YoCrJNg9`k4b9l@(ulqT7RAn(EtL@`V`sU*+;1N`QO>9l)%vu{) z<;2WBgs&s8+W zk8g>C;4}zl`G@;rq*a_@3ZtBLG-fQy5z8jlCS)Hvgw|BR6thhB;jE%%6MW1~q&yrN z_<;3$lw>Mrqt-CQ*#uvw%%K$9cj$!QzG$UB1^cxzF3jEXGOriZqAA8s^+t_L+ngj- zM`oumrLvHBu`}sEEh5^4yNLE~#E$Xo>@w`+cMxkIPV?#{eZ#WGB#b^g-79t=<-+-7 zS8`)%3YQ0%Zn@&;E5Cs!O$zqL64sHde!o72?d9_YICnK;n?vP8jd!p!&BPk=C#Eni z_c~5M>6>f~?Bvpki^Q?Tq4mAyQ2V&)+S~~_SNw4}m*rVdEgxHIfu9dsk=cn0Vzf2g z4_T$99J8|l>(`q&4GeGEx0?AKOdn_dNU($C$Iiu>k;d3Lv3Kf9&MA{ThcG&v#TxOa z!b□a=J=d7ONI|_q=cfnWh$K5b25C}jl)-*uE!5(q~@GB_7NWCS`g5F8SS;c)| zEc!_(*_@H3@o~9)tpyfxZu%)$JuY_ED%`G}Y3~Iy;`!~DedLDQrFW%wgLlLiwY?X# z#^2)8BR0n8`Q8g!;%DMNJHFI!z}PGSWW_#9SLef;j`xB&@!9xhi?{iUD5vG?fcJfT zEwgsC`F|gr1&b89{2Nbf&=_0POG@wQ-_p^#)#`3YvMbx9^2Q)YH z1L~XL!)tvb@@BmBGe;4v(Y_OSFE|-?mxroZ2|InP8ZE8chqsT$#{=%Q@p1TH5wG@V z_Il(AIHyt6Yn1Eo{r-3zdP_DMngO@`&#z?N)A%Y!zIs-Td?o9mWj*pQ@wGC(3iTPU z)koIF(sRN>SbL6DosxFD7AfLBh97P7PKiM^PfCU_73R|vLLGw|DZbE?WVLHCzW0|T zp;QHC?*wV4v{OpKDgXS&Z&Qa1Z+4W>oY+6Zi_aSSrvS5aa6aRVPwN>)?kHR+T?ibl zfA@-~gsV+Co+4@ARORXlxEIHIK~LjsSy{f+pcrp$ubq{3nw_O(edXJ^y1H5Er**Im zadqcX3ep!+wxkESIR9CRFN?nxmQ1C5EF;2$sH?8=KA zAmD!eXJ`ZWjQ@Lp+;Apfz->~7W-d1nU_BOVx!boDigjk0Oup(LSHNmi`Rk>kj`7m> zalr5u^a(iSS9%%{Jo=bpUw15z8tP($;akKPcRFrr*6y?2aKgaj?u)$UdmgDs+cHbQ zoSX<;>*LkHfA|i;KRJSF;pG#vV*M{G8Mf)x%r+HL>9!=~(l$@IftzlTVFd%;ZkG7- z-0ikV2@7CU{C5{L1=u&$_8o<+KGjZ*e_tA_Q?;G71$)L$;pIbtDL1qSmhU3kC!y<9 zBcLU{QJRu9zL~XT!Tm$euo(HtjTU+4*(g+;nV-Hra=z9gbJOR~iVbqHHO+Zb*}UG~ zY%{GWNK}&2b`<`2)&i;fH0IAeY<%OI?={VWZw?zdv3)|MFYW5o*3W`Omt%@jfX#F` z7!#j#Ci*0zhq|DRdpa^6oS&QC7GMzYptTbLtLe)CH)UTiR`+RrXFwYa=b=;t2Zggj zC#Dxj((Bz?RcyCLtL|X+F)GA)e=m3Yky%&$w-uCOjxLYa_8QB0;JiHkG5^6U##Lp0 zHg_;@bf=_tMbs~Xg#`0{3CXfjy-t1F?r`C0X?H#cEA2okX0GU)&^Ql%z=ZzU!{%qK zWdS(xoqfByW63@J9);!kToFBxemqvn#TL$*06f`y-t`n**7F1Px-OpAXA6ESO<n8!0rj-6!7w$nYH?B15*Y^slCrBfnvzuuFAn>5tER~+`9k3BspLbq1a zQ@B{TWo#X*!%2T zuYQ>+#YfIIlIEO?iW6RdkEBUV7d13nddb=`h_QbgQ_}V2Iveg`FiTFzh01VD_91X_ zmM`XvZR&4lsUTgg0i2hheZn45-3T~2-_28lfgex(7IGZBsgK;`&lXTo?8Lj&?vx{g=Bo>GzfUvjHjM{>X39jD@Eesg@PH>2wxYq;E$f)`-H zzD~+;3EdwHwO^CRY~N^fuYNrqE&VA1gV<~#FVBU%qaC3rdUeEi!D&j{pZc<()2+SaZ|}8 z#cxQ7oVtyi5f~#ma0;GRSg9CjyUaR8tLh`VUfjvy(3LQI%f9}r4%Z!6SU$6n+1q4T zR7!_%N5^S+bOMIA`3lM4|kTAH8^^r-(Pyap8dQojpPccs7{1a}pw7u_uPTqVg zDD;hPQ9BT7>F+N8eYvGzT0yO&duiP9cY_n+lTJAzdL&OLLgxN!yIAns)Ybrr^wx_u zE}i~MU>aoI?uZmZeJ05vT`2DzI}myiwK<_peihMqY>mUAZ6iIg>6@J8ov=8S_8C_! zE8pfw@^zL!rxfZ_p}`)zs4)}sqLj@_p%KwH3XZ^KR;ygdj`Jz;)omk+8Pe3y7#>}AAYr6aPj7p%3jdY@nn+j zN6-o{D$X!SkM!30Fw&PDjFVf$kp`=wri#4)hE3air(M&rhHq;GgN50=>6c-$V$n z4Tm}HTevqv9|S$d*Rlh&dIWYT1Jx;w%;V ziw=~50DHs?hnai3G( z-wrI_{AWcw?!lCZr;fY?{6@$BcaFTu#0dD4o#cd*F!ppFh3iQiivCcGeg7rch zw|jvCi+}S|r9}HG0*B!G@jpY>qG^ht~X9l~8Rl*1h)B=hI~$QL5e z&BMTpZI9#LHpsr|%%>40>_RQ@Vi)RuS{$u0X&r7*o0!zNm{DkD{^dl0H>vmjK{3Fh z^7XJgz@YdXwglW~RVCE19TcJV9Bu%7v@#spH>?`pa`{jd%X2uA=j|$ayqHNY|GtXd zA1LTXCnOWmRDiv&KMk|eyl^fcn(~XTM*e&7Z!e;Ov<%p;rwjD`A$whMj*T z2Xt)_>`jieWvU_>`y^+_$Q);D1DhWQ5Dp={pG49}=zdh=BWbt78Yj@)p{HExZA;|C zjpvlKBhbH0jvmN!GmLcmJY(;-Mq_WC+ekIU)3t!d?E$%S&^k`>ZM^7Lh#dxz8cBh63M+UlDj^V`*q~rq_NZ2JX+AjD;@#d zf23qnq(!^X`W35vXC(hK$nnv4b-xwK;Sr8Say*3`>wW4slQCl(2UU`2Qf*U#T3#H= zk{H!I&vL`Fw>1%`hnwa~~**Sg)l1S~d|AH*3se6 z-1l%|0QH>&-`#__4e`1NKNsg1v6r%M80B*<5q{0yCpE-l?I70p)1zIiPTY?YS#8;R z$L<`9aT(nPc{pV1=gg3OI3sd=t#Fy&KkwXaMQtXsQTJX2XP$&4G&%p=+<%8F@6{RRq&M4 z`X0M>K4rG-!C8R&2EGVj9|Zk5hZ}Bi!bd!V|1sjJ0NZJ(9%7be+*=k|&-D^p$&0-% zc?)deDp(Y^x|6)xa-POul(5HuJD5s(+gJ0m`68aWa981G%<&$qKduWhi8_`K+f!=|JB^TaA=ckCSaNxUF{jK1W+K$=LmLV*T$OvA(jW zbLw}mV7nIZO7`5lIVzE3O}E-`_jbY-_$=T~m8Y;r#qLyzmKyIrzmBJ2-T6k&v>WX& zt=zr>c9UQV;nDZqIBmE{+P=alZ7XD!0(J`j{JLe0Wb!fG{UVUh17sq@%0~6K_>UzY zu{1e?JAgtZ)v_mYL)%Zv#o(mac{uNVJMO-k(9Zl>Jvy%LWrujYb6vZ4R3pl$_Ed1t z#Olg-6rO*^@~g!9)cTzcwSP}V>WWk^F&kki-BHNuSUv!*7tx3;zdHZS*!sl!EspWN zWfffRf}f<;AL^T`f05zDVtJxdPU`L0sPe^TYy3&n4%^Tub41dywgg7uo@r*SHZ;e= zXOHAGpJCjNSY1BcyQWW|c5XJiujr{L#@Iav5sU#p_w+y2x4nE@;TO-Ce-(q)f9=Tf z?~cI!?{9e@!}Hd_`E~V;*ntS9k=>O%ZR%%lA!D|8u4DdN@KVgF^0V|tq=8Y@qY(^t z2Uxy;;^gOeJ5O~#!?CJ7a>G)!{Iha((4b=XH*LqwdzSVd)N+$QcO9fa8rDqnaX03$ zKK#HvK)H|H1AA#jIzH#mcmtJC{Q^;sP9=gI$%O&inTfE)t_IVku zGCFwrB=okceiiH|jGhnSPQ;Yd)L({TO*FvnLiA#Pw3^zr z`zl~ZHq?RVL@WaSX_BSmU+arSeX%DUk^S%{=zaS3m|%Fu1=QRdshRV~n!XJf{0kVaNYJQdcR4cb=Jct? zk84NopZw4BK%ERns)Yy3o{sQ~&Cy#M$Cr?tzbRzfq|>bY-OxuFPNFksGxkYXn{3=k z-yWRbBc?j=GH}?ObM4EX-g6DUfWHmaZ4Nh4rNs0^WIC)(eKX}fxZmI)?xJ9PIkkfE zW$OD3)V@ab8Q|~0I>c5uwjZ?h|7q-7;G(M5zSo``!!W=oUJwX}8B{J_MlmJL8V1;+ z*wM5L-fAOY8&Mfilg{b94v8mCDpOA>T4|`q?ha~6saV?eoZd5|c2d!ztVW?cgSWk5 zkoo@49w^`M^?bh%etXv5dtLV0Yp=_*p3DCcVAK5sFuh@QM-*^=q1GBvNctJ*sSM?Y zbwSfAbUhT7mixQUV{!hD%%CNT8A8_!cI1Dj8`0gKp2M5pxDE1Y2G~1)HWdcjE5-0S6weO5$7UZ?-(wj1-vRZLGd`oS(+XZOVDArl|X?s?QbGyjBxm zf7bU}jevWY9gy?;|B&zZ-k>{MS2GX!==t3E!@hYn+kea5JMJ3gzm2upozR;P^Imw? z`WITWV%)tHETs3RAc7rs)Ld}7_wA*$>+FYT0-1~m7x6Bd#HWxy(Ye^Zf3(& zgsH}yhwDHowV&N3R1tbYMxF3y^t)I_7RRqRB7l!kwelA)8+H-cbr*mUXDw_Miwesy z8+`{!ZMtABErZ2y-70 z_y#&B4b70wCgoZIu0v4T75oZ(p=?;w#X!?S?J?xM-~eC4Y*JcTb3UR{ov!x8;owHL z`3%sF3N!oBa%_->AI|^YGkSS{Ki7aZVMMWDetEn8SD;{qbcOzKM5z((vJ{`E4qtx9 zg82H^%D$L09duQlvPKbpR;{D1nw{HS&D{w-2g2LU`s7(QWG{NR2K3!Q@Uug-ol+WF zgQbk{41TVzY)t(-4l}4jtfl;H+~+LM%4!zbrsn8PYl81MT>Ouo3(s<6UxwayeEqz# z#(M7q>Gj;57gp2Q36*-%7r%g|H+eVv)ktHiAq!Sx}1dr-Acg8nAnBU#yRgyl3#H#TC1W}$oZOZOjS>Xc33g>jVf zfEs-vDnwuK)7+oBY|wKZ)@c?}8q%S~l%iNak(IdfuuEKzGGp8{t8F;~K2(xR3`(1h z$mrL%?-8Fau7SqJ2RHNf!Rp(#!=f6(jjzU8mKY(%In9<=m&|f9ORe*)Gj7SOC1;nw zCf_-$Vqk^AsxP$he|K@#h$R_fJlYm9wqNUs3qlt5WV@nis=%0sYfl9ts77G(KjFu@h9FjgQNY>=7$U-Cs$l3Rd{eNFIF`J&4> z<_Ivk3d?WJUG&)P>#1q0(VvoQoGThaGhGs%(eun9k1=aebzL=4mv(&bOPyIFOZ9oo zc+$f``c|Ru^eyBOpa!SXJGl6yl6=vgv`wIzUg+BX7)yD=b5A~JIR>rnba9is*OVx# ztyw^6*gLU#z72bc-kMa<5<%%t!NTThfwR!_H_7{vPSu^xj8a-W)xekt#T``Q_D&RV z|69~(Yvfi%FKPb!hVyNLYoimv@W!Z=)tl?8*$X%Cw1bT&5w4hyULA1|1^{Cpnl9B za+|!E`G90f6ca`mMgi!}=Ye6U+2DIY1W&Po>06gFJz4Ab<@L~tDdm}!`CB`!Vj9ll zAyeBtkt71tj{dArKaAqnIUJs#w6BW|zX#~LIbMcc$+ocO#p6M3z+NS&O&rs7VKK9) z(Awj9dXxXgy`fFk@=?$^rF+y4$8pcnR8$`7FW<>|u5AMKn2%(mi~2K-8!f-40SFj2 z;}|aEh=cGdppk^RlF$=^(tD5_DO6e&_0F;`87o^~?R6i$7wrOoWK>x#zQXtN3*j@? z>?+@Yz3lqRdRcSyUu&N9POsFB)26X2{{#&JZx3HN#ueuuY*R%K_8e?eM-Rm>2Mvp( zuAw6HKhnwCOe!lhvNZAQ9l*7TZ}+O!^ft%2{^B5O`&52UqmEBsa@kcWhHB1I!p|~m zS(UCCZNsIYjOEa1^N|Mms#ILH2P7X$wfon*&eT)wrw0G+bK!c8i~8aN<~S#3_V~Ee zm0r5y(*EQ)!jms?_;P4wg3Wf8;1Y zj)%NyVvO^IuK_weGw}ZAaq6_GkmaiUeN-duJ5nc64%@ceT!fF9!_4X6RPLAOnQL8} zM;dgeY8|fu{t_aV!*asYkJ>C&nW7{duv%MngY}InHt!^<(-|u1O z%@f_o8P{E(ez4M`d9Xl<-|6AZmk}G$U1pe#Z-m4TW5Sa3+>7<$_3Iq5UJG~%8^KYa^^OBS zfx8R1!tMQ(6|cDCeMkK1X&95Qc7*nRb-~Yl?>l}x^YgPNS#^{fRfu($lXXW2V0Zcb z>a7Z&VV&}fuVBBNm@~WzbwfS(daS%^^5;o;plF74zV7=o`ZO@K#5tuz8^dcwx|#Vub%l^*Mk+Wmvx#ojMm3jTn^yGqSarH|ddCgb{i;;8VtuHKiDR$L zrx8R*GtB>^3t!z9Ltossk-oTXw!6=@F)pjs$mJ7e4OYf^EFyb#qUaE_vRhm+CO#XOH5-wBmI=5B zOE(I5w&|ucrSm;s1j#y4@-|ltDAF0ANKb+y-H1^!%Us`ja^)@$OYh%AD{5_6uT$CR zOG>S5&|UNuFc-lbiCw3I`Gb+F{X(9F#f( zoRv^nX4@_xy+Yf&u($ZXyiO!xZxN22=oW__dy6FOEyC+($9+^!nB$9mNzeU+SfY)F z)lZ7QLiGJ@%GiN@MW_tgSM0$4;GAzqO$qMNzG7HtUvZm!h1g|=^3lGc5c%lY-1tUc zVa=}Ja!-oCrp$sdpi}=7-qB3=dbCSS17~$13`(=RdXOP;ZIYqsO-Mg8(OR=iYQIWb zEzdExx&P?SbyJ&}@$GtAtq`q7ZHBSMG7sa-d}qV0U*vwp!Zy9@GWHX{cyEo#2_W^f zA7B-q03Fe4QD2JIx(!wCZa3Is+7?4cZ(W1B3S*bMDS4s28*>d!``VZw~b96^dXYYENiP_eDjyp~x#zgl+JUp$pNzOF0qyq3d*H7%{ zEg;!1rEw1XOF zHg4o$Uqo9C@RTZGt@xmsC=+hnI-GHq%dQcHX-mM3G4}>Pk)><_Zz0Qlw9HYns(S~^ zd9Z_NBzifL?{4ec(1t`$+^D}PC1K744V6K(E>VUD@C~fc{|@a-W;8kvJ12r3fR1Uh zg>*c$dstGt)T0CYNsGSC{m!e|5?5Os6D3ZkP$mDnhGs zj|SZpk|$(enUYRBz-`)De7p2(AhOM5td<{k9=aIKqCW}!Zo8;vA6pYAuSQrcKWfuk zO-UlgYq4$WwSG%6hPM~}1+*53YXEC&vt{vp_)0?*WfS22bQT zj(5Rhw;fo$ceNNX*#x`Rhe4SWzS5XZ5%T-LVV9`nfhKr|R034KPU+j5T2N4wkLYqu zN;+m=Siz{1?ik4W-j{;4;{A5;7!wBYs~oB}m8wsZovE!VTaoiH2W^kfwq*)B>*pE;deCd8Ae*;VLa<9j`KJ^!NKyN;|yJ4 zE+xjJN*U-8KMb=*IJMS%=Zw<4B}K5>U*}X?|L(M7zhbbiTM~wyRZohOrE8X~bE>*y zVXJ{Pp(k!*>F3T+ZpukYMyrC+YU}1f_|abV>Gk{T~;nhWtr*^ zkJ|3Mu!QyQu~BQL966`0PWuf`M@f8JRmCDdgAXam~J_}mf5j?ex*H( z7u~xmU9dGg-Z@bo#GDP>gu2Q%9oqAm=x1+q0t1oBhaW~vr&I?&3*4RWIDDrc6Lvcp zI1%8jGk6aIC$SUzU)uGquH+_!oe;!MsRoujpiJ!@Qq%|UGUwnT@$^hvj_Dp)gmm<4 zGezI<(w$DJvhycpUOg|{wy)(AfuIbJF#dnu#JcO>-K9yqw}~`j@8{pBJlJS}IHt)drl~D!3|yA z!$;u8rtk|yZtHZ}U{eA3uCK}o_2CjB$%ilFKWP=TM!t2XKI-4bg!dJV) zZ-v)j)dJZwxbYEq(u430;CHiO1DjS=9%wxl9eV#$XGcloD?KZimGDvkwM=p$Cbs|7@3*FM`#G#%o;* zu1kisD&#HZJ;ajam3cTJ}O9X3GtFIdT9FlD|bQ$v0YdLrx zffTulxRBXsgCCHetVZ;(`26+|Ji=6w-6iD#jy2|vSRQ)c>1hotKEVcy#z1U?>F|iO zt6tdkw8g5qyJ6)s0tkT6XS(7Wk=EgXH@Wm{kfo~gg3`Ca9y?BwE1v^@ompv4>c__j zs>(HcSz4~=SvkQ5-vVlG&sUe!8DGJB8}m$R&w_qkIk=OS!sGBP35&`S`S6T=Tw8zkXrf8x{s|e+ zh(pAe^FDb<7Dd@mP92Oc<91otn3TI&aAS){pDJ+@>io4 z&k$EA=?C~r8^C{#UpknXWVR9PGkP0#9P1FZ{SV#k4+|`C>i)|;x-`LEEE?V0v2!DD z7x%(1!Y8o4`{a@;gSd2~;en0P5?*Ux{vP+3(&0D~-FrdTM4pAE>M+RGhZ#JBAO-6S z+`xHaOb$zzn~DTMB+2o^>=)lyth3zfeNpql7)P3>H0T0yo8e0%NW2W{^_PF^^*g#{ z_+;aAY^@4>-DuXw6H{8|{t{N(wcwN1qdbQ9u8yOPcx2{|=pzSsMU-puABJ(c^Cc)l5jaThqF9xM`sGkwKiJHx9qju~0ORCn7Zmae(JB4f(KEZy{0!|q*dLnqtHo-u33{k= z+}6^3_f~Pd8+K9ou}aI*8MU#VwcqkZCt%k2{fmBkn=g9swqzrE9{Tb|^;p0!ec;FzfO&J;~pjopf# z21#0|KYs!{Nh1#~Q0fDoq_pX0j&*;v2(P--0G+ehicHXfwZnoLcBx=*ejRD=_9R(i zM+ym@(uPjxAvoU@<4PB}o0PoVcwKs!qKAKnCVpU&bpX>TDQZPS1LSQD@C@e+N{Kh$ z5{tw)g>}%?9jEv~dAj`{zHlqh_pLsk%KDQ}ZN1>rTE7QP_nohHEjOyR>XL6&0)tGW z$A_Zxz;W@^CH7G3Z#^x&G`=hwy^Q+iqwwR?DJ{f~%n7tj>Qx&4if=o3+01`GD4R~{ z5&05m27flZJnUV|_vcw!p4S5&Uk-Vuo7PjR*}DVwM(L$n%hEB+uGX0O2%242-3@PZ zRO*gg^*J{5YSS{I&6i%vy+LduOD3M{YDQ zVD!$EqDLzdBKuxCWTq1Npg4Sli(9 z5Z(=j4>&i)x>H=5ZOcf=fp0c7c?O&>6ct+M?UZv|$1mxuM(o0Q8<2*u0zmhITJCA? zb+YK*1x*<}YPwn6?k3cgXW_#G^Oly4Xz?)Xc){nJVg@ee`T%fxHGB%Ka9Tg=#%X`` zg)7=Npx_}(Ctc=%R2lri2i%~M`R)W^8vlhHn+07>8RfL*CDz)suNxi&Z3)_hsZYAa78bgD382 zTp(^l%8f`_uarV^?$1%mTIfdyn)bIF$)DfaCSAnWz~4p+nyZ*U=OB6DWa)KP{_}Jv zC~f=@vkUUB+3Rt$WX{U1=l19}g=h*@4(4~@i&;CjJHnbUQ#y)ZwLU{21bCJ~^g}>8 z2?|gTT{TVZM&XJwubd8w?!E0s`)K#aYaM=*>fhRq^#C)=D8PeWHCTJb-k;rF$h%`DAu zKJH2NleN%JFidKf3c)pl=JpChvktz%+NGIYDl6=|J!*?(g++`}d~8q|gzKMqARFuS z>;|={ws3>uR=`$nQl~UsCj4?Mymhca*A)zO|ACnMfQ~#xH8>5FN=$=QC=&dK2Z|rK zH_E1?y`HSeHJ-U&gm<2#`x|BmoVni$wIyAMTM-A#6Q8fQ*y4*2W(X?Fb>9ql2?=4M z)AK{`H56|Zx<@`WtnOHGZ->io4+mNVcA`{Q4wA;6G^D3U{sW!vcIn>0c6aMK;zp~| z!#r<@tAIzK2G7*U!kSa~>@uscs;mg;(ac;YknblBb2*jQANY`ch)YCX`-npbu2PTJ z!Dct)0`)9SwMNwz1RqD`A|z02F*EmYtH7Zw)3{^|cVKu7l=b0Qr>F6c!20+=-sfQbvNOK@1S{gfvDSJ+ zH7NH#!!i%6*O2U3?Seli^y{c|MxfJU6<)Z?5eW`?GHaJ~(D?+Hw74C9Uqd+wTRd3| z;enqAeRo``XHaVFUJ(OQM_11(Pf|$2&XuK#PSor++@|z3ahmW`>F_5N^>s+bCrb;l zYC?8D^y+!;?$C}gxxU3W)O8sY0H`CrU(>+U{-@Q+ zB_C!8il;f4u%#c?v{SokK#Ttpc0hFNC$przfh$*4ff&X%LMLEpK{mIZc0`xEt*7Cy z#Ssn6+-UfIpgPnjzAqv$M{Mm%#vM(PwFbMOY9K$YXqW!h$t7KcJZFHc#x-KbTdN6U zvS*BF(f8mrYo!|Y4@c1p%Rx={^hGE1+;0EX+NCzk{J++3cdJ$!;n!u9DIo1uyatk{ zz$lE%r`x|@2iXI#jEE~IOW8+As;rcLIN=or|2Y5oxmb;}jG*u~!ygAr`Gbe0P4TeQ z$^SuHDqD=eSP2FOPU1!{7NW#Yuy!Y6?-`IHyONu2s138eAkL2EzV0QCY^ZY>&-D^h z8-9$7nM9U72Hx*mBdT*kXD^5^I_g?E_0CqcW=E@rdqFUG!zU3PVefcL2pY(5C_8IWNeRT>Ho`*ISLl{C24~^b>-=+(o{3K{rLhcX9&FH@A^< zg+WH!F74^av_qODaqG9cxji!WJ;Vo>CC|+}+}Y6LStXVUx+i4dijmJ@AU-IxRfbqs zOxk**JZEGLbjy@TYa^=zZ$yt!&Tn-pH=D*Tmg{E}>$##s1Z?Ssm z!1MjN(~hUNbwI9SV%CAFb;Z4aP!o{ezv+UMWsbmxed@We2wFso%Y=`7I`rLk=^vf6 z<1pxm%24az6I2;1_hQV^xO-wP_?2JQjwimsYzTxZ9^Tu~NxEK2C zq!$pzZ$R57HIN?zd1^o!d1zEaKsph??k%E#?me$+>#qi)L&U7yYo~X#>0zr_9(YjJ z*Br|=oYtI}g?%Mae{agzm*K5f2QK&?1m{K5st->B0uWl&Rv33SEKi&QyBFXC3CF^8 zu$_FM(JM1>FqyF^XLj!6C->*RiM#p}+j1W~QP*lz)9!qR_f39q^DB z7?k-9EIvRNchH^}^kiTaM&!NM^4^669c4?>nXXhNCOR;|=ihG>BVc|XyCylAv;H~@%}>r>G%gK z_>-$~grD3JyEAT^l4>h(f;n}WaM|ZSL|XQ+i)^=-=?@b|kh&pHAao$L!kdLJcOVVb zLc=Q{z4T$6s1gWkC-@6ijf(Z%Ye-o0C|6ohKlx1mp8~3pvG8UV zHu-2Q+Dc7hiLkQFNKI=5_4A&7ujfa)^Afp~8t@qUGVFk`N<{5fA5eGirJ4T@Sw-j` zt+aDC?l-^>(AvFA+#K!B{SV0zZy2_y_HY{lu&oJK(h=er#R;+>+{I`2_Ca3{LuzgV zrMF<$soE2ezPqV?g&RX-7T&~p0p*Q?eT(9&xRxwk0@8oqyjzIGeuk_oIzVe+kIUx( zwPzFj|MY=wkl{QlweYbyk`%bvDyEgPBx_Eq;C+B-^e|xNzzWqwRv2Vo7{Vvf<#XfI zf-c`tm@R1YSAi}*dPzMp!b$7m?B}4nfrBt!j=?_g7<~<3!>E;Xbj2FCbjK5gkG=^D zt$>t)+M9soO4h{mWNtES!hqTKBj#CJ@77?wgHH1$A?8cOQ`r{Q=q*#O*VJ5(j=vCGqE;aX&Z8xVKV9$sugN9GE}RY-)rShxg{5khL1PA`fEg4)-U~G2^}$e z$YovGq066^9lXrv@4TG*r_Rft{i)w&Q(XVc>kahn6n|Tc{`?b^fcdkCgQkBu3g3qi zqb7Sd@in>i9Zy{m&N$p3!`k#EyBWUEj2)`Zf!UkvQ(F@LFtDTM#`}S;Hmflz&}&6@ zOIS7+(D^qz3}+Hr)oSP;jCJ|@R&93Juk@}`-BpwmAGfo9U!cn$6)u&j6aS=DZ&zUeB?QDxd&IQ!0c;OV(f*%j_&Htna^IkaaY-Qdk}EJ@E__wDOg z)y7hJ?>>j>bj(Sf-y@4FM4}&x; z(9dRt&pehLrPN%n)LaJ~3)P9uD9z*I`B1GTe^_^|qXMjJcP^z2)mn98cP_i~o-3B$ z*&3y>x9IG^%$!`9g?9buhQTGU2e2iIlp2)hRRhpRa)Q5x34$*2d~u+OA@0e=^@ zBMT&EOlnb6J=(YAsyetU5lUU6fKK4@uXb(8wO@J4^-h~Aswf9~?BP4>8v_2TED*CL zrzJc`t+ZsQPU^OxO+2yNG5?Hed~r^8OB7mhdqDN`e#cVY%}+l$)ic+95G_;;oqkP6 zm}KeTt`5xphaD}oj3rI+;ahWN+@mi&xPxnZ5q@8KS`AxfYKMLUj9D$ZEEb5m@ti}` zp}Iy-<~V%A%wZ>{I{ z>0yDd8D!cf<;vpUGu?8{glq7f;9+2B=AN7%biIuO z*US}Jt?s;|X5$t5SWaA)hK$9_7O!#Bg6}7q+n#_(X9Ku9|be-VIQm*xlvyvT& z+=K|;0DOS{C;G}CW`W(VHK`)!eu0L<`$mAah^-WQG;T<|pmXb-IxN%arhH)uak-c;;?v{J{ z0|u`S_e?<-=t4DcuBf$TNe^tcP(H#VTy<5y#x$`DbXBuu>NRF_0x@^Z1eQGfzU*sG z_`6#(Apuy~2^DiHYAeoF$kNT5X(+SfCTEtU<=_zwUnEIO4NhNYp9`hUF)7p$s9~cOm(kO4TKd2(lSmE#zlsHs(n)btN@SN;jj?BhEyxuHJ z??YolXm|wDhQTsDCrggVkDN?p#+69YI9ZhxofiNH06QRH+ZM~6Qg2!I*>4=YlN
_#s_K16(*f^6zpX8%fiK_Ru}DdbTlYV);u zeHytWeUb{u+yewnk|ZS_q&QPEYbIGXmnTVmvCh*qvv5fo;J8YXQKr(Mn_WolOK~bC z?F}gi{}Q3JD&)N(N!{0)6rv`Ke9URid;|K*>S5v7b1-IXL>pnop8T)+Qhi!|-4(OZVK^O@S0%pS(4OY5yL!Fg*o<)&8Y8Un z7rgsvdjI`K-Y)in&aOF!BqcYb4UOR3S&Vpo8+=XC+caLC`n+yRnHXDYg55R{>+oiq zg52HLy~J6}JZ#UO0zL=vZ?xbkc1fQ=eyve>r8|KWdRr;&Thalq^3@6xi7qf%rdm*SUb%{U5vDO@usk_Z6mHt5F2||;AZe^QU z#Z_{)U@Bp5J>>w-2(QO;Bf)JWpWe|aC~H1YpIdmoP{BWa3^nPJ7DKi-U8%>~AhZxt zrooCGo-l$M>o}fTVR5ikoO;bU&zN)}E`^U*so}E?T8q#=p?FF=S3y-=0KRwShmbg< z?db0GpcVE|l#j0Rl{C|pH_h)#{*ZX;LxOCd?mDQoD?tpbKwp_rKvX^X9QZ>B}ygb&!8xgfS_OZ$SLzu6;QU zelM@G8nN#VN2UKGAr!{P~%(`R>obub3$(Ak-j?MW{#E2cZ$6384w05n&&M zdW5kEH3$=IJ>@7o$}atfMPfKCDdS6H{71|CgML<_H7PD+yUi?pl&hWSD|8QD5!>a5Th2Iv-oFd;8%Qc`iY177>4k%)1KKI{eiAH} zQW$*jKntNrFde=~`Uk)%VL%=>Tl5Erdq1<&3|sjSe+YuXny@-gY2z19{sN=lw?m@UqhSd21JN zqar-&wiL+EAPWhmU^T}3jSfn02Z4r>M?T&mQ9`&Y_>C_?IOU_dnfekhzfV4Dq0&MY z^@1bLb7sLaXgAJ+r!zzH{SHk)rRwER;YdRbIw;e^JYgwX@0?hA4t#aFf6Z3(h%G-u zM>r@wj-kyOsqDeAEV-~^(c@!>EgFIFQL(V1cz)sXh0BH)v3cd?%NCXw7MD~!x~Q;p zG0So~9TlaEAA8WrN-LI(!13tv#U+)_lA>iL#idItkY#B}MN#?UapTOn)2C0JKF*xA zu%e`}_z5#^E>@BmdXku@mpoRwbXf@%XwJ^b9+8!OpBdRp3m2M;D@q?PsrWrC z>B5p?^RjYt5lUTFVqPYe{I9GfkCzsej57}^{yqDQhe#U+oAShnnm8I|n8MJ0<^>Eiipap7V%tzfic%Ht!4j~p}H_Si_<{81&vW5{YUZ^4(G(z*4`4ng=yyNABJlR^|;=M(9j(pj%&&n z(S2>~4kNomjI9Eu!J)@t#9_kG^OtbTIo8dd+qZ^ar!oDabf(WmI0VNNsle4qVR|2q zB%HsCd&3akiDOasv11t1_aDym_v82iMhDT;+5B;J;u zt~d2!;RuBb{g?rvt2&WIAlyD^Ff$@N`spwhiLm*xJ6RM$7CwPRBTS*Ln@YW4!(67| zmW|8~;h1$g7+ars{LrTe?LTd^Z9vFg+Y~pK!i$gR4WZEd==LjF2wBNjhn2AUo2Qk~ z(|d*zq8>`f7F@JbI<{tCD73E(g=|uH*vDSGh5j1u{ZpTJCVv0N>U)P}C$#=BChp#G zHMSp~dm{IqLu*gJRDWXI-5Gz|^R@NHq`M~k?OM*w=v|{;eyQf4`VVFg$}WGaI7Rn4 zH9P*2?MlFAhQc++l(71nm$E|dnU&ptvG%}$gB$tl?e|_%PtCk<)E&0=ycJK)y1Q}d z%JWnEE~oF@^Y{E*rr(I8=lZ4Y^T4C%PxFD%`3Tc*DGbFwSj_bQ6hh}4Mc{wn_#2Ll zW$1V1q5Iz~35C62KSE`Gy)+a;BT;{T0sMmD_ zRPYV{%jy+OPY0E;ygRI_V)}tD^!=5g`$ag%0Gw`u3cmUw2pjI`%F1;`TI*Llxw0bWTx9bP}76fumOnaCP4^ J)4kuz{69(Uk<|bI literal 0 HcmV?d00001 diff --git a/boards/holybro/kakuteh7dualimu/firmware.prototype b/boards/holybro/kakuteh7dualimu/firmware.prototype new file mode 100644 index 0000000000..ff5cece0a7 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 5409, + "magic": "PX4FWv1", + "description": "Firmware for the KakuteH7 board", + "image": "", + "build_time": 0, + "summary": "KAKUTEH7", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1835008, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/holybro/kakuteh7dualimu/init/rc.board_defaults b/boards/holybro/kakuteh7dualimu/init/rc.board_defaults new file mode 100644 index 0000000000..b5ecee9894 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/init/rc.board_defaults @@ -0,0 +1,30 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# transision from params file to flash-based params (2022-08) +if [ -f $PARAM_FILE ] +then + param load $PARAM_FILE + param save + # create a backup + mv $PARAM_FILE ${PARAM_FILE}.bak + reboot +fi + +param set-default BAT1_V_DIV 11.2 +param set-default BAT1_A_PER_V 59.5 + +# system_power unavailable +param set-default CBRK_SUPPLY_CHK 894281 + +# Select the Generic 250 Racer by default +param set-default SYS_AUTOSTART 4050 + +# use EKF2 without mag +param set-default SYS_HAS_MAG 0 +# and enable gravity fusion +param set-default EKF2_IMU_CTRL 7 + +param set-default IMU_GYRO_RATEMAX 2000 diff --git a/boards/holybro/kakuteh7dualimu/init/rc.board_extras b/boards/holybro/kakuteh7dualimu/init/rc.board_extras new file mode 100644 index 0000000000..3423728dab --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/init/rc.board_extras @@ -0,0 +1,12 @@ +#!/bin/sh +# +# KakuteH7 specific board extras init +#------------------------------------------------------------------------------ + +if ! param compare OSD_ATXXXX_CFG 0 +then + atxxxx start -s +fi + +# DShot telemetry is always on UART7 +dshot telemetry /dev/ttyS5 diff --git a/boards/holybro/kakuteh7dualimu/init/rc.board_sensors b/boards/holybro/kakuteh7dualimu/init/rc.board_sensors new file mode 100644 index 0000000000..284490fe13 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/init/rc.board_sensors @@ -0,0 +1,13 @@ +#!/bin/sh +# +# Holybro KakuteH7 dual IMU specific board sensors init +#------------------------------------------------------------------------------ +board_adc start + +# The KakuteH7 dual IMU comes by default with an ICM2688P and ICM45686. +# We start the ICM45686 first to have it as the primary by default. +icm45686 -R 0 -s start +icm42688p -R 0 -s start + +# ICP20100 baro on external I2C1 +icp201xx -X -a 0x64 start diff --git a/boards/holybro/kakuteh7dualimu/nuttx-config/bootloader/defconfig b/boards/holybro/kakuteh7dualimu/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..33dff54bc8 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/nuttx-config/bootloader/defconfig @@ -0,0 +1,90 @@ +# +# 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/kakuteh7dualimu/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_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=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0050 +CONFIG_CDCACM_PRODUCTSTR="PX4 BL Holybro KakuteH7" +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_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_USART3=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_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/holybro/kakuteh7dualimu/nuttx-config/include/board.h b/boards/holybro/kakuteh7dualimu/nuttx-config/include/board.h new file mode 100644 index 0000000000..a182be3ab9 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/nuttx-config/include/board.h @@ -0,0 +1,433 @@ +/************************************************************************************ + * + * 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 holybro KakuteH7 board provides the following clock sources: + * + * X1: 8 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 8 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 8000000ul + +#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 = 8,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 = (8,000,000 / 1) * 120 = 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(120) +#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) * 120) +#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(2) +#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 / 2) * 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(2) +#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 / 2) * 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 + +/* 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 holybro KakuteH7 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_NLEDS 2 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_BLUE BOARD_LED2 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) + +/* 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_2 /* PA9 */ + +#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_UART4_RX GPIO_UART4_RX_5 /* PD0 */ +#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */ + +#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 -> not connected */ + +/* CAN + * + * CAN1 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_2 /* PB8 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_2 /* PB9 */ + +/* SPI + * SPI1 ICM45686 + * SPI2 is OSD AT7456E + * SPI4 ICM42688P + */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */ +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2 /* PC1 */ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_4 /* PB13 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */ +#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE2 */ + +/* I2C + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */ +#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_PIN6) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +/* SDMMC1 + * + * VDD 3.3 + * GND + * SDMMC1_CK PC12 + * SDMMC1_CMD PD2 + * SDMMC1_D0 PC8 + * SDMMC1_D1 PC9 + * SDMMC1_D2 PC10 + * SDMMC1_D3 PC11 + */ +// GPIO_SDMMC1_CK // no remap +// GPIO_SDMMC1_CMD // no remap +// GPIO_SDMMC1_D0 // no remap +// GPIO_SDMMC1_D1 // no remap +// GPIO_SDMMC1_D2 // no remap +// GPIO_SDMMC1_D3 // no remap + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) diff --git a/boards/holybro/kakuteh7dualimu/nuttx-config/include/board_dma_map.h b/boards/holybro/kakuteh7dualimu/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..1b076f9c64 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/nuttx-config/include/board_dma_map.h @@ -0,0 +1,46 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#pragma once + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_1 /* DMA2 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_1 /* DMA2 */ + +#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2 */ +#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */ + +#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_1 /* DMA2 */ +#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_1 /* DMA2 */ + +#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2 */ +#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2 */ diff --git a/boards/holybro/kakuteh7dualimu/nuttx-config/nsh/defconfig b/boards/holybro/kakuteh7dualimu/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..bb53d48ab1 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/nuttx-config/nsh/defconfig @@ -0,0 +1,252 @@ +# +# 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_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_PRINTF 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_SPI_CALLBACK is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/holybro/kakuteh7dualimu/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=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=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0050 +CONFIG_CDCACM_PRODUCTSTR="PX4 KakuteH7" +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_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_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=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_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_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=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_TTY_SIGINT=y +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART1_RXDMA=y +CONFIG_USART1_TXDMA=y +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_RXDMA=y +CONFIG_USART2_TXDMA=y +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +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 diff --git a/boards/holybro/kakuteh7dualimu/nuttx-config/scripts/bootloader_script.ld b/boards/holybro/kakuteh7dualimu/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..fc0a5589be --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/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/kakuteh7dualimu/nuttx-config/scripts/script.ld b/boards/holybro/kakuteh7dualimu/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..ae07f4bfca --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/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/kakuteh7dualimu/src/CMakeLists.txt b/boards/holybro/kakuteh7dualimu/src/CMakeLists.txt new file mode 100644 index 0000000000..7c0e81062e --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/CMakeLists.txt @@ -0,0 +1,68 @@ +############################################################################ +# +# 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_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + spi.cpp + timer_config.cpp + usb.c + sdio.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/kakuteh7dualimu/src/board_config.h b/boards/holybro/kakuteh7dualimu/src/board_config.h new file mode 100644 index 0000000000..01b7787df6 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/board_config.h @@ -0,0 +1,225 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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 + * + * holybro KakuteH7 internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* Configuration ************************************************************************************/ + +# define BOARD_HAS_USB_VALID 1 +# define BOARD_HAS_NBAT_V 1 +# define BOARD_HAS_NBAT_I 1 + +/* Holybro KakuteH7 GPIOs ************************************************************************/ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +#define GPIO_LED_RED /* PE9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN9) +#define GPIO_nLED_BLUE /* PC2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN2) + +#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 SYSTEM_ADC_BASE STM32_ADC1_BASE + +#define ADC1_CH(n) (n) + +/* 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, \ + /* PC0 */ GPIO_ADC123_INP10 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ + +#define ADC_BATTERY_CURRENT_CHANNEL /* PC4 */ ADC1_CH(4) +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC5 */ ADC1_CH(8) +#define ADC_RC_RSSI_CHANNEL /* PC0 */ ADC1_CH(10) + + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_RC_RSSI_CHANNEL)) + +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +#define BOARD_NUM_IO_TIMERS 4 + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 15 /* timer 15 */ +#define TONE_ALARM_CHANNEL 2 /* PA3 TIM15_CH2 */ + +#define GPIO_BUZZER_1 /* PA3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM15_CH2OUT_1 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA8 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN8) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */ + +/* RC Serial port */ + +/* PWM input driver. Untested */ + +//#define PWMIN_TIMER 5 +//#define PWMIN_TIMER_CHANNEL /* T5C1 */ 1 +//#define GPIO_PWM_IN /* PA0 */ GPIO_TIM5_CH1IN + +// PPM in on Serial Rx (R6) +#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 + +/* Power switch controls ******************************************************/ + +#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)) + + + + +/* 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_LED_RED, \ + GPIO_nLED_BLUE, \ + GPIO_BUZZER_1, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define FLASH_BASED_PARAMS + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +int stm32_sdio_initialize(void); + +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/kakuteh7dualimu/src/bootloader_main.c b/boards/holybro/kakuteh7dualimu/src/bootloader_main.c new file mode 100644 index 0000000000..cec6abd467 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/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/kakuteh7dualimu/src/hw_config.h b/boards/holybro/kakuteh7dualimu/src/hw_config.h new file mode 100644 index 0000000000..03823de861 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/hw_config.h @@ -0,0 +1,125 @@ +/* + * 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 3000 +#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 BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 5409 +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (16 * 128 * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) + +#define OSC_FREQ 8 + +#define BOARD_PIN_LED_ACTIVITY GPIO_LED_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/kakuteh7dualimu/src/i2c.cpp b/boards/holybro/kakuteh7dualimu/src/i2c.cpp new file mode 100644 index 0000000000..e9f26f9a9e --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/i2c.cpp @@ -0,0 +1,38 @@ +/**************************************************************************** + * + * 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 + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), +}; diff --git a/boards/holybro/kakuteh7dualimu/src/init.c b/boards/holybro/kakuteh7dualimu/src/init.c new file mode 100644 index 0000000000..2e0210981f --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/init.c @@ -0,0 +1,266 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2019 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 initialisation. + */ + +/**************************************************************************** + * 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 + +#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) +{ +} + +/************************************************************************************ + * 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(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(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)); + + board_control_spi_sensors_power_configgpio(); + + /* 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) +{ + /* Power on Interfaces */ + board_control_spi_sensors_power(true, 0xffff); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + /* configure SPI interfaces */ + + stm32_spiinitialize(); + + /* 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); + + 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 */ + + up_udelay(20); + + +#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 */ + ret = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", ret); + led_on(LED_AMBER); + } + +#endif + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + return OK; +} diff --git a/boards/holybro/kakuteh7dualimu/src/led.c b/boards/holybro/kakuteh7dualimu/src/led.c new file mode 100644 index 0000000000..90c6e6edbb --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/led.c @@ -0,0 +1,218 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#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 + + +#define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_LED_RED, // Indexed by LED_RED +}; + +static bool g_led_inverted[] = { + true, // LED blue is active low + false, // LED_RED is active high +}; + + +__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], g_led_inverted[led] ? !state : state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + bool value = stm32_gpioread(g_ledmap[led]); + return g_led_inverted[led] ? !value : value; + } + + 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/kakuteh7dualimu/src/sdio.c b/boards/holybro/kakuteh7dualimu/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/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/kakuteh7dualimu/src/spi.cpp b/boards/holybro/kakuteh7dualimu/src/spi.cpp new file mode 100644 index 0000000000..ec4f04b057 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/spi.cpp @@ -0,0 +1,50 @@ +/**************************************************************************** + * + * Copyright (C) 2020-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. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortA, GPIO::Pin4}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin12}, SPI::DRDY{GPIO::PortE, GPIO::Pin13}), + }), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/holybro/kakuteh7dualimu/src/timer_config.cpp b/boards/holybro/kakuteh7dualimu/src/timer_config.cpp new file mode 100644 index 0000000000..aa48eabe6a --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/src/timer_config.cpp @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * 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::Timer3, DMA{DMA::Index1}), + initIOTimer(Timer::Timer2, DMA{DMA::Index1}), + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + 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::Channel3}, {GPIO::PortB, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/holybro/kakuteh7dualimu/src/usb.c b/boards/holybro/kakuteh7dualimu/src/usb.c new file mode 100644 index 0000000000..70eebc6fe0 --- /dev/null +++ b/boards/holybro/kakuteh7dualimu/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); +}