From fc887a23afb47299cd32ad1e7a7e460c9eb20ba7 Mon Sep 17 00:00:00 2001 From: achim Date: Fri, 6 May 2022 16:09:14 +0200 Subject: [PATCH] boards: matek h743 mini --- .../init.d/airframes/13012_convergence | 7 +- boards/matek/h743-mini/bootloader.px4board | 3 + boards/matek/h743-mini/default.px4board | 84 +++ .../extras/matek_h743-slim_bootloader.bin | Bin 0 -> 42684 bytes boards/matek/h743-mini/firmware.prototype | 13 + boards/matek/h743-mini/init/rc.board_extras | 16 + boards/matek/h743-mini/init/rc.board_sensors | 22 + boards/matek/h743-mini/nuttx-config/Kconfig | 17 + .../nuttx-config/bootloader/defconfig | 93 ++++ .../h743-mini/nuttx-config/include/board.h | 493 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 43 ++ .../h743-mini/nuttx-config/nsh/defconfig | 226 ++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 ++++++++ .../h743-mini/nuttx-config/scripts/script.ld | 222 ++++++++ boards/matek/h743-mini/src/CMakeLists.txt | 67 +++ boards/matek/h743-mini/src/board_config.h | 237 +++++++++ boards/matek/h743-mini/src/bootloader_main.c | 75 +++ boards/matek/h743-mini/src/hw_config.h | 135 +++++ boards/matek/h743-mini/src/i2c.cpp | 39 ++ boards/matek/h743-mini/src/init.c | 182 +++++++ boards/matek/h743-mini/src/led.c | 112 ++++ boards/matek/h743-mini/src/sdio.c | 177 +++++++ boards/matek/h743-mini/src/spi.cpp | 56 ++ boards/matek/h743-mini/src/timer_config.cpp | 82 +++ boards/matek/h743-mini/src/usb.c | 78 +++ boards/matek/h743/bootloader.px4board | 3 + boards/matek/h743/default.px4board | 74 +++ .../h743/extras/matek_h743_bootloader.bin | Bin 0 -> 42684 bytes boards/matek/h743/firmware.prototype | 13 + boards/matek/h743/init/rc.board_extras | 16 + boards/matek/h743/init/rc.board_sensors | 22 + boards/matek/h743/nuttx-config/Kconfig | 17 + .../h743/nuttx-config/bootloader/defconfig | 93 ++++ .../matek/h743/nuttx-config/include/board.h | 493 ++++++++++++++++++ .../h743/nuttx-config/include/board_dma_map.h | 43 ++ boards/matek/h743/nuttx-config/nsh/defconfig | 226 ++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 ++++++++ .../matek/h743/nuttx-config/scripts/script.ld | 222 ++++++++ boards/matek/h743/src/CMakeLists.txt | 67 +++ boards/matek/h743/src/board_config.h | 237 +++++++++ boards/matek/h743/src/bootloader_main.c | 75 +++ boards/matek/h743/src/hw_config.h | 135 +++++ boards/matek/h743/src/i2c.cpp | 39 ++ boards/matek/h743/src/init.c | 181 +++++++ boards/matek/h743/src/led.c | 112 ++++ boards/matek/h743/src/sdio.c | 177 +++++++ boards/matek/h743/src/spi.cpp | 56 ++ boards/matek/h743/src/timer_config.cpp | 82 +++ boards/matek/h743/src/usb.c | 78 +++ 49 files changed, 5365 insertions(+), 1 deletion(-) create mode 100644 boards/matek/h743-mini/bootloader.px4board create mode 100644 boards/matek/h743-mini/default.px4board create mode 100644 boards/matek/h743-mini/extras/matek_h743-slim_bootloader.bin create mode 100644 boards/matek/h743-mini/firmware.prototype create mode 100644 boards/matek/h743-mini/init/rc.board_extras create mode 100644 boards/matek/h743-mini/init/rc.board_sensors create mode 100644 boards/matek/h743-mini/nuttx-config/Kconfig create mode 100644 boards/matek/h743-mini/nuttx-config/bootloader/defconfig create mode 100644 boards/matek/h743-mini/nuttx-config/include/board.h create mode 100644 boards/matek/h743-mini/nuttx-config/include/board_dma_map.h create mode 100644 boards/matek/h743-mini/nuttx-config/nsh/defconfig create mode 100644 boards/matek/h743-mini/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/matek/h743-mini/nuttx-config/scripts/script.ld create mode 100644 boards/matek/h743-mini/src/CMakeLists.txt create mode 100644 boards/matek/h743-mini/src/board_config.h create mode 100644 boards/matek/h743-mini/src/bootloader_main.c create mode 100644 boards/matek/h743-mini/src/hw_config.h create mode 100644 boards/matek/h743-mini/src/i2c.cpp create mode 100644 boards/matek/h743-mini/src/init.c create mode 100644 boards/matek/h743-mini/src/led.c create mode 100644 boards/matek/h743-mini/src/sdio.c create mode 100644 boards/matek/h743-mini/src/spi.cpp create mode 100644 boards/matek/h743-mini/src/timer_config.cpp create mode 100644 boards/matek/h743-mini/src/usb.c create mode 100644 boards/matek/h743/bootloader.px4board create mode 100644 boards/matek/h743/default.px4board create mode 100644 boards/matek/h743/extras/matek_h743_bootloader.bin create mode 100644 boards/matek/h743/firmware.prototype create mode 100644 boards/matek/h743/init/rc.board_extras create mode 100644 boards/matek/h743/init/rc.board_sensors create mode 100644 boards/matek/h743/nuttx-config/Kconfig create mode 100644 boards/matek/h743/nuttx-config/bootloader/defconfig create mode 100644 boards/matek/h743/nuttx-config/include/board.h create mode 100644 boards/matek/h743/nuttx-config/include/board_dma_map.h create mode 100644 boards/matek/h743/nuttx-config/nsh/defconfig create mode 100644 boards/matek/h743/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/matek/h743/nuttx-config/scripts/script.ld create mode 100644 boards/matek/h743/src/CMakeLists.txt create mode 100644 boards/matek/h743/src/board_config.h create mode 100644 boards/matek/h743/src/bootloader_main.c create mode 100644 boards/matek/h743/src/hw_config.h create mode 100644 boards/matek/h743/src/i2c.cpp create mode 100644 boards/matek/h743/src/init.c create mode 100644 boards/matek/h743/src/led.c create mode 100644 boards/matek/h743/src/sdio.c create mode 100644 boards/matek/h743/src/spi.cpp create mode 100644 boards/matek/h743/src/timer_config.cpp create mode 100644 boards/matek/h743/src/usb.c diff --git a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence index 3b2b51b4e5..7cc6fc4d85 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence +++ b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence @@ -69,4 +69,9 @@ param set-default VT_TYPE 1 set MIXER vtol_convergence -set PWM_OUT 1234 +if ! ver hwcmp MATEK_H743 +then + set PWM_OUT 1234 +else + set PWM_OUT 3456 +fi diff --git a/boards/matek/h743-mini/bootloader.px4board b/boards/matek/h743-mini/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/matek/h743-mini/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/matek/h743-mini/default.px4board b/boards/matek/h743-mini/default.px4board new file mode 100644 index 0000000000..a6bfd5d938 --- /dev/null +++ b/boards/matek/h743-mini/default.px4board @@ -0,0 +1,84 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_OSD=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_RPM=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=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_LOCAL_POSITION_ESTIMATOR=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_CONTROL_ALLOCATOR=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_VMOUNT=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_ESC_CALIB=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MIXER=y +CONFIG_SYSTEMCMDS_MOTOR_TEST=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_PWM=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=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 +CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/matek/h743-mini/extras/matek_h743-slim_bootloader.bin b/boards/matek/h743-mini/extras/matek_h743-slim_bootloader.bin new file mode 100644 index 0000000000000000000000000000000000000000..9a03d6bfa45a72833640a48bc26eafb524d3c1be GIT binary patch literal 42684 zcmeFZd3;pW{Xcxpy?2%@kV(Q4l0aq&kPVz9pb=b#ndD{}G%RWnY@HCq8)6{>+E8g2 z2x?@pKxhj@E0Wr(SY-n7YtWb|YHO|S3`@U2P@_;UBq(=CU~blV-e(4EtMqyOp8uXd ze)D>rx%ZxX_VYQP{c|smC8-m6qJM?^zv=(3!T*0?fL!|pFTTIy$G^~gc&SI@o}dUZ zocB^s#QLq`GLiF3+@+q_+9}@{Hch!OSXv=IB7ULH@e)PXZxZY5@m}J8gnG^^F`kQt z$nEE&36)G2qKWAnL!{|~5_91EVClAthE05@2X`p5iM1cyw!TMSx4tK$uC^z(uBxz; zBdPl4loDb}an{?jk4G&C`o;ndPdbc6oIep8C9255-;t$@{g4k#pZZl zeJwj)a`aa5@h+m2_qFwu{<5uS#V_Mg#-dQ<&JSJZyRN^X%I0CBjO-_hZP1|#Nq?5- zsX`R)qW&xkqe*HfA*ooB)XtZP{tT|uE|Jb{NcTH897vSRy>7F;*PWB-y03)ppnFIL z>3P9T8%U?NlcCrWnZ<#~y&L}>>dJdr3F@IMXn+)V~g z%*559XwlZKPL%7l*+b=o!4o$ZM@rjposO$r;kZcGw9p;J9a_ShY^T|r=(3`oSr#__tFI7;jEZ6vygTabVxAob#XmOvH|BbjHw{XIwvkmexi zn@vt?B1X1y6tkL85{qO&8Ye~CCKTHh19HbBH@vfnu7ssTajU_AK9~?%QG%UgP&5Xs zljxeS>a!e347wbOd%i8Kh5M68XOKFP&Lb&E=a8xjgBPubaOO4=i`#su$56ZS%?&suwLOM92FIhFV@i^w z*gC$~{aCe!X2-hY>K^kP_7Dqud#-6C%I^0FM(aC7dEl*L554spnPgn@I(pr!v?cK_ zYUz^66xnORGl%D|Wa~Rsg%~H+lbu8Kya7F%!ac9Q*0Z*l!LoZ*l#7@I=Q#JVCU$az zfmgq)r#9vDgt#!ay7o}&L zA|0HIwQFtNaDbQ#E|--ZxbpLLQ74Jnc6A?Jk`{}*$g~9fleZc4;1o7&wsW8Dz4G&_ z3o>n>xwQU@9L}YmEy?@mwY;mLyfc~fv&g*9|08cS@@U@wewP=#cpX=0odhQXD+UZh za^t_lA#APY04I$4hIGcH8Je>{+v_(7DOr(cc)!cRUnz4$VU78Ip?8#v7?V5i%+jAs zo^8!b&W{e|6UE@VEI*hfoJ^QKCzRVGufx;m*;S#Zi}J6sxKpJ{&}wLnoxLrT_mymL z3TaU;-dEb|##oNZnlujgBv+NSp*y#wM~+E5>(e<|@7VD+;Y-q~M~X%=Af;lwhECEs z-pSe?Uu&r+7#KxP3CZnh8j#yZCqC(It_Dphcr%S^7_W%KFilJM-7 zIPAci^(YmK^@%NxGA3fTxAqfrOfhdHN?pGN_-viSp>#SdF2%xjbMc!7?7x7%-E2%4 z2XL%DnO)D3P6ijxM-crQr1)mHg}z!L3SuxYH)w2$$@=U9$>u&A=i&|+T5(Rh*hyC9 z_-685x!Z40F4B?c>XWMq^$gx>$q&xa(6D(<@ z?TsGdCe8E^Q3RE~Lt4YnLWZk@DE!E>p4yQ=cOE-GQepYmQ>;p75~O{8%Kf+dDHoKK zvfmBg_-iaR=j-SN2N_3TcEI~}9hY7FjTTF)yf9B2c{00M5kK0-ROz>ch$Acb4yKPns}RQtt;8}fa`AO zzy9wE-G~2qrDTw|B$!KzZQ}mNOPsH*|L}s4tF`Q}<&|d#3!S&3jVD#ttPj;C*+(vr zjl6Qc-|nQZNaA=GXPGrSw~8u`ew;0;RgMh^7K_Uw(abrY8KrijRXPWV`BrD?)!^E( zVuH&kjgz+73(lA&k~+ebBuy%M&YixFD2{>DBC1^OPcWHr{b*pn)FAP$6r8I$xTogC zN7J3jZr+kxrBPlSp6rbB5ao%1Nw`v_p>HCtTIIFj)KLD%L8|<*U$Dd!Q%k4Hw8NmFW8A6@cZ zMwHA`t=2^zuDhL^C+#ZKg6BYTf#Wc1oLA*Uk=0@4*;=sqvikoGALard1_Q4Ruf}*a zPD69Dl!aZI)^BJzyP4*mt!227wUgI8%9$+v74IhXA85gRp8O$hJ=8bBN-`tP5X;%x z2xpQszvY`IM(2q!ua(YhXhLh5SA3UbszmquF-F!d+q0_Xrw#}r&O+5l@zV=Jj#fF; zuMz+3iQfHGEw?>tH{Bk&`!nQ|?I!RQ(^O%C=5(5UY4KvD$eDtH_RyR7X5m^c zF$V+PLAKjdF7y;?*VTy{al4o;rih=ZX?uzCL7y-ozk~J9Yk}$eg$a2bKl98J*~z2I z6L`+)NHDScTl?!;*m%-9bHqr00%du982zQw`z!f_*`e}{eMz1BrDD-g!p=~d7}Y?2 z&1jG?VMIsto>?eEluuOlzpqaaZ5~~5n#d~=edMMyUY7epAA?L_wWmqjsW_r%@D5yB z`Xp8qvybEJufg8;_{lHSyzNNq|01@4-Vx(Tl^mcsg{5&#w@WYEM|9*#3`3mkvlnYb zl6IHxY7>J>%!b%HX~yl+TW!=#Zy#+d?fNh}s{6x{i`40J$du{6zp2D_wF#|RUq!pm z<-ev1#(nEqU9N#QKCk8(EoFQIqbSd-f}y;uakJ@hi*kf7dpuo?cL@G`uCW$p9XO67dVsz*;r)$P5=Tj}`UO z2764${UR~OmClg#*P$3%53z`i}y_h*&N*&r7Hmt?6qoiyibv_Y-eeZpVq zjJc}*w&*U7({#TdjS?(3i_PM+%O?(=dm{$(>iOB_TXNlajJW<=dky0hAPYWuxF@mHyyrerK@)f^6;-Dzp z-VWky!(3m)UVHLqiFDc=JniVaC;wDIqK_C$R3Z9L>XI@(G=JM=I__Q-Vr!bu%PUX! zQR@?x+WgDX#>H@ikXo>w&&#W32?)&`r$?AFV3PYu+en#A%-LH8fK=MQ4^j zN-XKEZD!8f7`ggcgQbtIff0Wi~F1%BoR*j5lmNM0xY=f91~mE_eUi#G)*c48^3tiJe9Im&Ns$hcx@<{DNLnOHEKc%ggGNzpHA%}JVch&B z*(`kns2eR@yhaNWoYv;?(vt^p#s?pHgkiUr2hTYK8^1FZl=5BF)*P_5@-GvmN_8Yt z(cq=q_?J25>@eNUO2-2VtR6a^-8TSIh%!~>p`-aH*87D)YW(6_KY7iyQiy_?-9|{G zn1lP;9EkCOiq#(TnoV}CkN1zF))qZ>-aIUH8pTw}FLTPI;V?}zig~SuX8wshMrn%P8zHr!)^Gw6Jp31DEAs;5Wfu8MI^82r;5s5YrFlTRBA>rfE8{hK-+bFyF%n zjWt)Bw3%_f^lHIhL^$Q9VV5TpSmEqLm6ByCu{16r%F*EvKQrlIC%gVmO0Py+493~o zL&L$=o@qGBE8;x~YwGNJ-_a(f^~m*PK)13?+T-e!lOzT6xGK)f@060(SA6CQdO9F;3)d`Ns3O6Z{vaOdSf1H0^}XVALoJhe=wa z7iVSFr&yau2hywe0zW-5pcQQgZBp7nqC7o7(wyE^=)XzY;OdbYw8HW9YHHbRi+9wz zGNmIJ7hiVc9tHnw%KAJ$7+#%V;O+sGtoz{_CxZF`{|zela%$qe%fPlV~r-0_X#G}#+AOt8eQfkUuLyF^P-RCyw`UgXW}}{`4Wg; z*G#t)<&nNL58cfl_^~Q<2Lo5$T>gvviHT!{0?XcAAPZQ7NGI& z!Q*QFfo93srO`aJgw9vFiIMqW_e z?jQ;UUZuHFnSM~bs={5Msd>#$N(-T>OJt?Vdi%IgX^lUbJRrRj!XZE0dG_`kU}V)G z)9jJd_)ga5=RTQ1@eN>|Q|1o-3pfeAi5M}z{bqaFh@z&yOYkl;Qs5+XP)D-0=7Jf;1l#H(lwQ3G=5;!jm`?2$~p+=Jt z;nO^lQAcy)nljwPOgD1C(!qgnUwN&;iz;N>G-vwVE+aGu`Dsq}Kl$4KN4RIt8s#qo z8nMVj{4QPAV`*Z-^lZS)Py64n2Yl^V^S1{W??(LX8gBB~yC*+p6ceVg5)bshgc3HC zc=cKdn}$p_+&y^}IF3*WXQ+gm?cuc&ZnUBQw-Pf#CDhixf=(VsI)ii_hgCJtLCv+O z$;LKEBiwBiM}^u=>3_|x`l=wqvw9R1dJK3lc0c8U>KHBFQj!8ncT^?rk>W{Jzl}e| z_@mbIYVE9+Tg4(k?=Qe#Jk&DgZDQ<^NoKDv3YrtYHy9WK9r^~R@>bCXsJ}R5#W|n*IXU)bcs%h^<_YAWVJ30X~ZX6NS4=Y6eEE1 zIK>AUC>You{F4lwOsLFfL*K|-T1JBMoq~K|1y58LjKtGXJT36BT1Ij5YEF5z?;+PJ zsnK;%I_r8l#Md{3cx^UUV!5SxgG8BB_~iHD|DKAhYZ5!%#e>r_t)VY-%H;l3=`#3- z5zx)rJi~#D!E@3mk7ezCJMS9~^nlOIYfY7|$ia&SXt&1p+dKx0sjjcHC8mgBRZiLP zU+|l@D1_bm7nG&@l*f7)dw#v`|9*BA zk3%}^F*u1aN$T)4+GBhcDao@(dQpnZ-{V@~i3IeR`iRlxx_+7y#3bp049k=f)pwb3 zwZspuCHQ$S);te7W}Q^d#5pv}=zploq$NUm!UPTzXf0 zXA<^{JsDg@utP+5hVK_ZdtM@u48IT0x$j*dghIE2_7weFOd232Jz!k(mR9*^OI0DW zMcvXIcUKnlL9v+C>^=${YHf|dz1Rm?FTO%7y&7HhM@afxRnA6##Va)`ogkbpw(C%4 zTHn{Q7FR2v_$%PcL5x|!JmOy@`a6(*fh0gj#Ji684fFXc#1iFVa~pht>8g0;g&|&f z9;so-fKsc%GRF`2Ph!+5uMI-qrF5u89xX~HNhI^Uml#{m>uoyax9@Py-jLp&>A@In z4>aq)o8Lwtat8*fx^Uw}wZni@oe^Z~2;o=cuZKWW_in{3& z6`f{tOS-5Bv}gD2E#F(Y%hOq&ER+7vv z-#M9CZ@{NtjF_!&wlE3i2KEh&;vF(dt3f4~^s)I8b5yauISTqgwyMO$g&80JJ4<~uekV^rN#J@x{wF)iTh$x|nA1SxTjYtjTfiP#D*Iw4SfB zt4p{WFZHT}M($yKNjvh~<_!;{?8o&9Ug+6H1gDu$_$Z!L*kSy^{Yx=%*g+$d~xNxq{Zb4z}>_$0GO(3hMbR; z4+h==m#k4P_5bJkZy)~Q`se-I`d2mARx%s#DAD4f>!`xhU|@PMD?d$4RdhmG(nl9Y z-uozEoQGDh3RvezvIQEVxgMHtQh3sys3|exnvh>>=Wt>q@rn%JjLd+{;E{@@;Hb$L zRfUlvyXQjphUSgSY46EZd(}Axs!(c%m&VDJ@vuE^Sk62vC_m1z-NiW15GV8l+z||X z9=uLHf)|zM_bacJ`yN-geL3vk=$}`pM(_H^Pk*%hQ9bQ0q@IDR{w3+Tr)ajNm)MH+ zMwF>vp5Urqe#*5&z0Z*1r0IMY;j?^>-uChx>W@f78t2ugrTb@hy0$Ifp)PRE zV%`yRM|vO$&7I}SbZlFGu4z5Xdvv{P$MSd=qmN4Kdp&mEq{L7gdW#SuqQ^P@By;Kd zHndg#cex2YdaiV?z%x7)yz=mc;H4v#dzQ~xc2J#Xv~_Xz_NGV|F*o9g>3rI+&-Qx~ z{Q-53^;VBVG17BQ!9ZD%^=)Xi^lp39gf;G!k5o1+KUvY4h6ald!JJ&rDpK7+P%!8!1-CS0eW7R623yn=yA&_ggC&5tV>o!M=_SgG-PuB=~Y z@~%)42p~4&Ht$aLKI_{anhC4;qtR`p@Jj&&aqLtV7z`rQ$l6TA6yHrV-4 z8spD~KbP^=a4AIF-vQVDLFG=>MTP_WRAOd#u^~<1a6ouFuld7DZE=S9tI+$wenCuV z3E%I9{FB!@E{(}iqr@G{k5x1@?b7~Eoo9_daR_kyj5g*3TNPj5A><`$wJg_~q~$`n z+rV)cTH}?GF_*j}E%A#l;@sw89K@s%8<&rBvHebR?g3wBFeerb1qy z<;2K5UkE&3M!?I3T7IX_Asf|utk??!wK4w{{@q|M|x5yv7Ge3_5{9Dxll) zI4k%vzQs{SEY7m>8e`3oo_39~rBfnnT|Gzm^2a}c7OQ0auEO$~heFSJt+z19mLf&B zhnEhiKQRzkqn-!$9?wI=oyMQGtaV`3EUOupv_cWcRat2kYNj2G7njgcrT@HtsxbQa z>wMhZMQsI&`=P0}T!*7;y@M*Hl$}`YhvV#AN6q_gi&6^AHS2M{h8Xq5yx+i4OSDvP zvpAw$N~=k}uGwQ-@6Qy*9^cO!oZ)^lp^N&i zpRO&~!Ej%1|3_b>hFUZwwKie|EI8s_ovkE-wVyl4+IOyrT=Q|Yy^A+HY8Ynk(9#pZ zzz1!?z_V?$YPgzDw5474xY=!bXN2<^U3@bkZFa>CUoS_^3ap^x@eq&M7HSt` zrwWL~bhNbR|%;nfT~ zC0i;TW{)d3Azx|D7B9&Bl^v^KWtgs;^0hCF--*$W^V;rdVO%7W`{C)tppw;Qnn!0% z1oofAC*(8T-Fs`J97k4Pm-ZQd(%v(I@yBg?tOdWetY;R_uV%ABYmm9WuM^e5Z|GK! zMd5H#j)b+}DC@xURqUI9HuTLl#YnVHZAk*W=bpi8(i#0e-Z&IkKZHGRH4wecHi9Px zSVov-R|~(jkN>UI@=z(#cD-C)GY^;^Av!#cnhxL$QsV~o{cF%tkp%5-Fwha~lhZ>d zZ{2V&R^l3+`yS?Bq5L$2^G}9wKEpJ6QBeL4yGDXhV7>xkf(N!O6ICLh-7!E;%<#`nv{>Tk*ZK3*M)6Yr(Khq7%vcBSGF!%r>+FPfqs|$ zsCs?|clEp(zMp_bw)O_V4Ahe@rCC#BEd43%zMof!gJk4-KdQTD!nFKD16O;+ns^7Z z$~w9}aL}m zyofGbU{}cEg>%YlmiBA_E>T;1>XKTVH4b=vIv>w@=1SeGcKxyPn)|hy}{)yE&&-B!d z&i`Z6e*5(Gub(WhS*YEA{4LCj%_#wC8s=qf=EbPliQ|(JciYJsYpX>%(xaQmslsiX z%0Gbn0;FdXCm$VHBw4Xs6RV?I2O1tcINB%Jp}`Q2y!*?#gWGU>~SbCZNO49vV=1&qESV==j^*OYbEoJ zbeG4w%r(5k`3+#eH--A+T_3Tzv$KK3=m%SSJrXf9DJ@oXS%ZP3;qtXYXn)FAhjs7d zUG_E@Sc(xu8Y7F@2tchIj$RT!f6h>#r(atV;zL5cvc1*=s+oR-wa?bnUc-w=we)x} zaJr4F(H704u?v|0aqJvoTv%gQ^xVS7+4{4w{WmPgWX)fFr*{noPQXrWXy$-l%`J`) zj5=7K@EbWbP!7t*&i5kSmE$In3u(JR6W`r90=@wlD|GLL@lx(=#!bb8lj4Uur37#f zCb0v4JHwVKrC+EYxXC2Q^^v7Ya>Uuymd7Fnv{&*(_$TaTyN2sNdUG%^a!BK^<~3KI zdras5fLQX`yNUUFzfr%iI{6l}GMigi6$}gvR<6-awJ5Xs%12Mbmy=lniD^_(A|zKD zx6l=3fd{h-8i3p8siSVQ^bVKXakZH(o5H^90&m&CSu87qfqx9xfa&${40;~A0i`e) z$i_OeHD+@=hm?T(QAjV3guMjo$$VwVl^u@>;tEBCrwjZx1_i&1uqV2W*-&<>w`VW? z1>*(it}%)$W+R?=s%xw)XCtl{1=gvwi=PjlI`Bib`IZeDuizgYf?eA{erIFNPBpo6 zr#iNMa!pyyS2eS{bdzUw@ur>Xm~Hm1k>;5Gr`4#YnEnmJE&k}3w39KHg~)|!y3&$M z^v_Hq`oH7)<+W?=bfW+8TKW{%Zlqaw&(i-Q?Nklz$%t3bc)1MTH%4*C5O2!C>pY%i zZHI2miJfY-HBH2HuK2IBd{z*Y9aY@rCqiB>^4^} z<8mzdix}U^m;Vf!!k>W?1=U|M_^)#n4BR*Piu~};{_rzJHm)^bHox_fjOTo;cW&w! zAGv8=Z|NK1KJL6)@&@Z=7m3oMeJl2|$_V-q178Nlu|Fx3sq1?4-k_*6{S97R+#|$W zR$p)T&fb-8kc@S`E8YmV9f!8>@P%8R5gPqS@QAhK-&;-__Q^}%rZ@3En_?iw)qjz> zn^JwTN-)Oci->GoOK%m@N1goQJUGs%5izlZ0$cEW<7&31M!sF<%vWXJ+$#&_%d*C- z$Sb~k%ee4vnd;VEnf%7*UtiX)>$SWwziTAFt~ce4bvNC4HTjM5waovS%e=F9%o`T) zYwRpIx}xLbT}G#QQ@rgRKZ&96o8Pd?vY|%qK?~d)Enl0~mZHs}*A+bXzrLW0M~hcq zr#u%oUON|WzkQwc*Zq39Kl%0R@Y~r(($@8!ecik%0W;J)d0^&Iklndez@q5o z#MfcG1nsA7KncR#A{b=eMVpJaIHRG}++4zU2_)IZbrD2xz%#-DY3I`=b;-xe(jH!kLWavD+Za8UPMWiQP+*WAPM4ouG_|GBil~lodc0pVG(<0ac2EWoi zaH7&V9vZtC{ab!*%)Mtcy-NJSE954ktX_ZciVfFa;Of4q$oFAS;Iu1Ek@6VleRMfnNiYaOP#e#ZTexiM4-Fe{vwq<*+u4uun1_@9RU!7Jfj# zYZuBeyj_Ru9nNGsQ3}=v1Czm1hrOy!>gWlB6zf`~H|8vq$)qpTcJ~+R$-ThU2QKMu zIZ@grj=NvgSDl9DJH@8zl1@;|7&zJ#t9omL8f(o2+$+2*GsZU=`18xb2J{0ig6iOf z@@zjVQ3eidGp;QCb#diPVk)=#zX`Nqm&m_6%b^B@P< z2?f_U*dc$RBPYV+9VNq^mGQ~8$iV|D!_kcXGTO^<^mY7g#Cu|J6NbAP4lh+)QKbse zf2&({;-~PQE=v5V6SLl)B#nVL??N@AitE>3&asmn35;jvQ*2{_scHRfUeW;XgTZ9e zq%L0jpmPE=10|5Zf8wMA(b);&!nLk!c9KecoT6}ZGDczrD*AuqtXJ0<g@Mc^c2MIS$jq$@F|HIiIdI2=ZDz3MjHN#ym71dte%0j z(}#K+(CSXui%54Au-}Y+Lnto~@&|2jwvdLIMQm(&PWFBRXmEPJJ5=JQdgcKaMK{ag1kNzfWe=>-m29>%3=%>t;$fCnn^-ZhyILs+iLMlsXIVR`tJ}1Yd#v zTc4@R|AVS`cYJMjF1iM<>v~VTp28wW6vi9ctrOkVhKyj%uj_$%b;ZgVLo!?U9f3O>Ea@^ zin6d_|7Xd^jOUsL193qD>p(CdLGyb)q|0P7U$~F7yUt5`56*B9^>5%`gt?ef;F}W+ z6swOJvsMlUx`$1oS$qt#@|?b)Wn2mLe=cC{ocGnv?0DDvD#|Xl*YVI*k zY*(}B$N?%O=lp1i;UU3atpPV-%ZG&VNY!7PX!Zv60oxK~ouEtKpcdI4sb0}T@n)Y| z(tg%Q%*m5&6Maob)YP&gs+A_^)~d$XS~WUWH^9MDe!F`6EL{exu^xAg>d3k0QRm@e zwvMl+~tWc?Zl8RC&VaP(M=*=jVT0F5R5`1+qClwkRPO>=7 z$~wEb7l*iat=+5yxp>EVGw+(@V_B1 znjo6a!lLO&J=p_Y#xW*`(|WpRlbt_B_Rt)%BA^lN;m3|v^ctIT%)QJxU!CkCQ;G7aoAlb? zOBACIa{^87Feh*TS2yVW>+bd*CPRG$+=G+PbaLPG2ISIh%Jc3~y;Y?j^zhcPUW=|& ziHUHwz3kWX4xFOY=u*WP-9R2twVe_Dd>`rOd!}|pjC6p{o2_cCpkficUDehUBT-OS(&}+-Zc1`cb=VI`nGlA~eeJfvTSt_LXGzZslptv_R%f_d(Z(cv|BxWMcV^OfA2Xxry(| z{KPid0&CRYWagV7hxV`?cr~dlcrm>1hS0w2*}hxndlDKX|OrdKAec@#3J~!$VAwOAx$aSDzoCg^e}<-QSiS*K2Y1| zw4Tp{{XF$8W-Usy4h34_>wwv0A6JFBKZQ5zG%^%82=D8)xW0kw2ZYra3cS*iCeBgy zGe1y;?4iKEJ{Aj6({~mUdUyn~?eCzLht|{1vl3!mTve?{;L*cqHVb+~w?1$I*26(z;D=;2jS zRp^uwT>Ub9FvQIsx2G0ftBF#it3=vkkMO~!fD)M=<`YtH@Attg?yagqUdr?!zS_mL z*kOl5%rU&#A|+m$=W%*iJ#b*$=(cfEk&C)GSNJ{a(!E!yOC>EM?j8Z% zLmv3rylwBo{z5Gl*UN=Nfjsp-#I-pJdXG5^E+0jd4Bb`8V#O}XkHnDFlZcIHi2wny ztJTwVg_QC~ z!3rBtA%lZ^AANTIBSeX23*(jA}CRV|Aka`|xS1x^{9YmQN^10kJoG#Km z+{-LlO%u}g??R-E4%R4YYKL9_xi)s%Mu=ZR&I5)XqE_D92)J)_F&n|yVO|n46|c(t zOPql8igJ$!bA>gd*S${X)VIZpju2dN*??uI3O;dbKG8pkWD<#9Y2I}3PdZ-AgDrzs zX%fwtd}>w~o%mbbADc40+zgA#E#fm0PCcM2=+cN|+D4^}5@F%5G>d$<5UtCIKlzn@ zg`(4eU$Nh2<1;Mz8{32#tOU*APKE1po^e%5>ucSdPCw&M7s%4HGN18}lZs3;K0fJ} z?Gsq^CN$A^l1%1x!;6WCx`?eN>HR)KVpSoRPjBT#Lvy`d=S9gciYeg8EyVk6j@5Y{5zXu&fqbwi_0L7}(_215&N6ufRj$y)u*NmuZeZHzngdp1{k@ zy&yjVyx3j=C~bys@GHFXNk2(@t&Q8o{Ab|@GQjkk%(^=ce&hWe=u>$XzJyhUpr!Ds z-g=;3Bonto^T*_1c#75@_D_t_d!5Pf@{s1DCY^o?ej!<3Zdd8v&B^R7SMT?d$&uze z#J9w^{CCDUPagJX#@y~5g{v`UruVSl5_5<5Rlk+*Xo|=zJ(+;LjBDctbhi{KZap`k zy;;|J*gqvE9VM+XUA`iP>bZt^mG0;2*(i?tUiBA1Pf~p{(r=6`>Lm*v?BCSSTG6*@ zCm;4d6w}vaQ#QG2c2Tdp=;J10-rQNFaQY%e(4Urz6utg`@o&%{m*2WV)*U`}*#GmG zDd=l;Oa}g!#iaVudfieAJlKnRjnaGaVSh%9!N=NP1U$rfEnR1S_9lES|Io(9J3;)3 zy-2Ck{}JV;#+(e5vndbNqVMWPt@p$#LI{?#(6-ifzT=&gIj^|z!t+^<`D z5^t+wxVAKmA)H65H^{I0AHvM*P964_V>e!3AE|u7&xbzZ)cRB6Ug!O)u%E4vzHN`l z#ydwG)pjfRk|6w&?ikdG&wqK?zcglD@8fSoiWp5%j48^mi-<|rzMQV;BGTGoOf46= zD5Bgl@VuG~xj%xV8Fp`i!o}Eq38C+#fF3|AY>bRoqGR&0S|nyvn_%HB2kp_P6BK>S z@4I=e-ggTmFeBu*U4`_{KHv0wGKrNGyw@RSS0QU(kDXgx3d=^!DrZ7liuh8uE;6!P zrx}ZrTG4Wg$aFAoZ^()dX2Y!+=PD6%UStI(`RbJ z0b0MCzVl6<-1 zs7|`OXu^9_Q7I za<+xp*&b;m`Xxvb5@`AO)-Uc-D-N<9}zR@O!&znMft51 zW17CJu=8uWhhe691)JKUU$vU%Z40o4oQVkxm}rPl&{+nz>a?u(Dkm?K>c9I`#fw9(oOpyRaZ|>|OisyLJ4u zHgHhl5$r@>8?lVepO6n|*1umseYfZT=4&>}L_jv?KDF0N@3@Tfy(C88Yb@t*jw)h) z<~w-BxT4I*P9!^xedjq!(ts}(J&G1H6+@Kvw9W3sb6NK+n$o{{APFa2@TRoP>7qQO zS2xD0kF?l9M>G5OcI)-ff~l;`r>fv4%J1EoSnIb6QZRq_<$dn_%LZ8YR`{T$7NYFY|69ljNbN=48?G*gdY0P=iP}4g&pFc-F^8@cObE+ zsW88>TNCvl#`R3+DPSM6j;&jQSlV^=(LD?+uK0}?xhtaE5}Fn?y*GB7%;uZ;AM;I9 zv{8rs3u4&pZUKc@!Jlr5$e3|5A~O#~SQ~&6iZ-IUHK2C~?N>Uk;}EvislbWh^Um6d13VrUy#<*af9Teew+jA@cpgnY z!*=OD+K`z)UR?FhLa_vWk_R<@PGgZqwJk7Jhv4ul)-#_7-1nI`5g1$Jr=j$ zKbX)q#ngrIu-+J+*j4x!8E~8%{i;!%*I#@2!Tws+BE>=9u&eOH>*Kz2SK-Wmrimj$ zk-el1F$tycOIxE8>%=i)a+?JnZaBda$>L{Y^AKfh7Bk_U@koC}#$oXYVvp;@h%?rl z{RLWZi~6>G1s9L9C@}SxEtnDY-jd^&f0T0x{0*}y7{1+Bq7z4oqZE>#+~)b#7DZE= z@$diE&_4!I!vb}T&sR7hBGGF6OTw@1i0GgA_BilG;=)I7d-Qf!SWga)De97Z=vqDQ zfAhhccF706ZGYm0Z}KY-eJeh}+T%XUR|Mg6`Gs$0J#pyUKZW}E@d_%d7@jbGtHaxmLNzoeAj=OP__i?WrS51AovFX|An;(fFUK>n>z}J=ZesqgfnUdn zIZnR&BfkC{@`UwUUDONTWPaDa(9!g*@C2RiM!wFk(SM=-4%++Q9hiI35G5#GeV8Ht zj7YY1Bta9>;6TLmFF%_nE)vPEVyx-=eZ+5#zF(Xpk{!FnNHZe5RQidayxF%w+$?@A zkG?i`jJwkKtrj!=Qze_J&=DTD81+#8^-*8+H3C;NPwQalcWE6V({0R!_W_38 z=3%W0MSUAkE6_nKIrxf|OF~=l0<{JyJlTWR1Yn77nXAb0gyldEYY*Shw-^@>-R@Ok zrCzMJ8=B+2h>ciTZ;!*3;yTec7`O}l2;u}pSq}$X!BCVnW+N!G2QSM})ihJ%bFzPY zi%9QX89X=toRmS>?Y{+5!bmH+He-v8LlTx$_=KYC6=HW7y4RZm~SoD8=`7uG4rUGjzUq#Rd*? zgqcofxbstaL`EO;3x*UC3F|VM@>d_C!C<#3_TsA+b4DvRO(Bbh-sEQ14y+9O&J|mk zeU;3|j?H&R#kRsPx0;`gzzDWu@Ap+wP=f!=<-BZFel34hy#xBLM0nG32M`TBz;XeP z9cQaa=F?vGzX=$b*E|ziqf0V--xz9-&H8cV&e1%KWPa-ex6qDO2x7LE5KL_=)x zSk^3F<4_X#T==GzKkD?*S32R5T|U5Ijyux{eaT-2-mstdv3MI6n^!B16i15;B9iqs zjAhny3)XYCvz9j_b8^a#c6P#p9inLqII?d|e zGLXjh&e@%}}ICk#Rna9&vwV znz%u+=@%{gbB{X#oFwCbeA7fr=fAfXiS{Co+wpycV4!kHm|*CL@CR=_kCuBwEmL2l z>5^<0!|g9biL0kQ1@!3eyCZ~UTlQaDOToJzXE9A=>mHu-i`ZwTImTMe+Ppy{My-h! zGd)oi4nR{>na1*o3zW$OI3-wr-EiQ?L*eHvL=yby+Wi>Z&mAJ>JV0ooHdY)Cl;Ft< z-R*Fo;98kvl(}<=nDU@c^7b)G$}4~EvtT}@y&WsLVyxdR_*lPF2mXRlQAVd`3^!KK zgzcB%o5m_eBRFOB;c#rWfcF{0<=5UPkn(HqHF%HMo@*ztu`&r*$KW3ax#Si1n^(53 zi#q-0l}+oWcKrUzrpGl?Gax%?mF1h#)3@(_^NM|4rq^~kBKNm;2d+9?6B*`#X8!y8 zZ+`ad)-ZHNo;eH5nFP$)kocF-cOYOdgqN`S*-n%I4!4q~xI~4)(GA+!x262r&hTf- zx9kIjJ1y_q;zAy90BU~uU+VqqbZAdEZdr_atbaPQRbISh?{~H15_?(w8`!C*L#s=D zXSZ6OqPNp2!pZV2MzL{YFfcC|{%+Fq;6Ch^4Ue+OHTdbZk}2knLw%z_RVJK%X~VNJ zgP6t*n`DyqjE}{<{1$ZiO+>tG@IB_qL?myebk@}^S;~GcPxmw;miR1Ui7ge~u9Y~S zqsfYE+{}%~wjPjor0SWL1nlswL*>;L52Mo$;na`qYpl-v4j$kG(H9!`7?!5BFi6paF!dPNSU7x_#{!;4i|^`Ks@U`A zIH9oqn;4EURWS;dDJ{ZRGk}H47=N~W2y?iBM|lV*f$CV+B(<=6=5Y}AL149h8TvBM zOTkaU;gX4hc$2tz%j-?o@twif3aaeDcc$fA^l`eiB3QJBs&-3zT4%q#tW^@~{Ibo$x z4*x9wUc#sC1m{axZZj{jIKL1NAi6vsy4hFFKESsCjQH+SE__?F@b!oe?2i$a6$9V_ z7{I#Tz6kcjC*6iKzyo-)A)d>=&IPPM@#Tz(q3EtDq3Es=owlpoob`Zz+f^RdSX?Qt zif`dk7L$N4FDo0|^VNkZv98^9+uaRo>L0y~uiXC3TaS3Hco)7Ul<}x{H~hCwNpoFE z6~|mw3nIXfyVM&i?RL$TPPvXsiDf6*Np=%cC>CUWI2L3*xVYqJPi;+YifGzm*Pl7H zH3>XiQqw1i?=`XSPyAgT_w1Ri5lsiN+9;E>DDm=tY2~>s_iqWe!k@W+OT(6krVe@c zmIrV>2t1V9)cIfPJ+Ni>wR+mqySFStdDc6f`L2Bbmgl~!&3f()o&3jTx3mrW7VlyB zeUL?So7}MV1OS~%VaS8$2D}CFSLEv85i?5uY+~F+ zv>N6)!aT-GiI{SqF-T3Ses4lP;LZ4IHy;T|%w@W)hNgPRM=w#jL)CGeua{x*)QXS`?p1$0Z;Nj53=v7Y?SmBH^v$sSbXFC%VVOwn_Kwx zs6~eZ$%sb}2C9N#?2*^X;t1(X7Wap*2Zu&jHLSpo|G~EZ9wT|bXB*ZnzJ*%cxWYH- zyEsxj8&t-JhrW@6QPsL9afr|TProRy`p7nD_oMhJXnWuf)Q)jBuRKV?A9 z5L{Lk-@S=%K+Pw^GRBjDPGUNwn%jTbv~NpH|CYhHrkw>zzB16cu%sbC(qPz)$zoy5 z6E}EW{`#VY;Ol#OE0b0s)_ZUg)O!s0a?{}6<-EiwM(4GwaRra^2HPSj zp^$Mm(c+VAwQn%qu;2B=x(%E{_rI5cvkqf5dA;Ya|V;g zxB{Mq!H?8)?&zD}wfFi=EB?K<<>4ET6YHu6{8as{B}~D;TyFZVPkAZ&+1R*|(HomM z6nHy0OCssAw{v+g@S|X89{~UNT0aNes-Mpm&d|36bu{-Y9{1%>|4&6Xv0pd5u4M;$V>0|YI(NE^8TO3z6HLCD((BsOwvr- z(1sSIH%i*HkY1pL7AY4cP1>PQSP)Pv=o%=vQ&9*P+2XpI(z9L!bIzPO=ghf0=ehi! zNfNb4EAEZyFs%vqo6nUJ=L>e~Id3a^C-rNh&$W`HndUY9tz5xdR+`(s^AHCDcDWc2 zU4j2ld0`I@9-}ox+vugb(LOs?+66@2J2pMHY3^k%*R#nD-PT=-utU1cjonc_yxMX( zazdN3VZm^pT@xGl?cfuhMUbKXwl8A3Hiz|o;v~6&@R4oW%DK%weC$|vbB_?4i+>Kg zg}0o!GEkquTQ%?|=PRNoDwdPAXYrk<;Lo8^Fsa$r932!FO;tJu-rA+vxoc_2M}+dvoRrN{HwPnt5SV} z<=p?@p12cFEJANdah&xUbMNphtTs*)vgcvv!}~_?<8ON@Yt~SDo2NoqlBYA~z=yyI zAc*dB?olF)`_^vpre#g`=q40UI^*urJdX{UL8p}^#(i53DL*&v-?T-s=eH>Kddsp{8XJpVteu0AH8?n|#{j#PyPa=-6U*M~N`K(Ju8ap_->0kC z_h0x%VDtN|wv;(f;_PK*Nxle;uX`H}X?3XU{JvY(*C|4yraLma@;8_V*2_|5rS*De z<)u2!wI%BtmdBO@#iKB`e7mAKPy!uuoAi+)T6kX-e38ibW~GW2*fU0{5S-~p29J0v zqCOE|C(h0SEVgHvElUqD}JB)j5`hECN!(yzjy zrLfE~D;XgN%(6H)Zyw{8PwGtCjA+MP$HJ7RQUBy+Ti(HhIlz&8YatQngzZoW?t zMYM5G$Z6uz`1JX{$e06;OKVwN!1U_cPRD$oLI3JHt+7sFoy#5RYnQDxt*cWaJ6C~w zKJwIjUxfbBI%Ybs;p<20lq6j1^qm{)lvJl_{j&83*I!(pwxM!^7q)LNJu+_N@{Qwu zx$Ku~@TBonY)PGx#=O5=Q&p#!ob!EA;xBwp=<1Zr{5oZU<2vh<3`d<} zwy(xh+4(VeDhFlBMT#tYoiZM&C*a7#k$^owO`#Xjeo?bYjySSM;Vi;1ggWu`D6hA(5jH-TMHgzq>WhbRU8C!upmm{3?p$}&qhU%T=;Rtaqx=ldC+E^2|s zS9H*SC`7vWkI|mZcYCwaR0~YbSga?;vs;-3Ghfm`ge1FOsdgHHUpOEsnat75-PTb3 zd#m<5$!B_R0CR^$b>4*-=IaIqC^xyq>OJ>>{f`c2R9cAdG~gfoCP{^!tmbahowXy^ zf2w?5#S-v;^X6ZeV{E0|c29nZ;dbUT25#vwKudz|FyFg3zEbH0!o=Ppjgm%7Ky>td z9IC-?5V-8Aw|9_E#U0XKh0j0H8r7rYJ~V8%Zikc-x@WOR>_p-A|;(sJ`HjK^kO+*o`UC@7F=_av>J4!L6;zl z1<;I4nIxUG3h&$^T?aA$XM^(^`ZYbHD{Ji6U_~a4+gfK>qi&}?YQ%f9M?R%B0tz|Fvj$%|`-PKcw|o0lDMLpGh$=LL>f8KL|D!@&-u&eq3X zf~*yJG84^mw@C4JzIsa|%Pw`3t_<)m1@6!%T|&VpU0UcZ!}oxB@_FvX3thtEBDB)2 zicswYTG%;AACHI1Xg$=8+)6gHBgO5fe)S|vmC)+XC$(Hxq2(c7S2AFyA?o)Q$l z`I39`_i0#0zWu`YDg5~Q1`XkGkJS9b%T)^!B)Rz$U3pmwG_1HuiPd>o(7M3Pqkspa zm6EFSvPJi}IV1AN&E|YRxSYV(IM?@_x0=O5*M z+*JrVdxflb9RP=dW~v9F{f)8}plk)iH7bM$10QyJPc{-t>`eDlGRuRlS=Kc77VE8U z`WD5&;7{l%kXikD8Q*OR^n>fCSAFCPY$Z!BA$ypoqpIFjh1`jP)JXdC>KDY`pGHTo zEbK~_<6Sah{{?F=&FiqE3#|f8FHRQD9JH1yB9PxTDe=-Z56d8VtEl+`JKNvL8YvpH z_U*1)t0v$`bu}XQVdot!+<3@s$49v{U9^&4_b!*?OIVK5QE9i!B;&lBeG8uidPz9U z?E=yl@FF!G+&)-j?IFsaJQL9PyYl_`1AYAc_%j^W$S>=}Piy6+uH>q6SBE^^6~-%D zgVZg+@ERlC(}D5i zTQLA6!U?xr;0}|dzHR_C7PR>G$h70*v@CC$o0+EDr*szMn|!VqPQ$^Sv&uNe^@;YyOKamPs_Ix}SRLLq${kxwkAs6O7oMTX>Pal$Lfi(b(18 zCUvVbDQUWlhC~@Q=#b*XbqGhey<`u116Pq9(D%zYzcn4b#tL6y?{;Zcp05e{kD?^h zQwW6{wp>W5?I3!v0tlcXe*2Nppu`#p@G@N9G)YoCZ7rP)^xZ&TE-+Cs7mD1Meg z*E?Iu_t`r&;P)}`Qho0tEv-5n^Lx+eFynm6SM5TM!-26D=}xZdfF9)taDJ($k$yk@ zWA4Nbb4%kc_&i`)ce>+z5wX~{M{tL@og-Qe`$6|?ig+%e^_;?Xpw#wHy7&iB>Iax_ z6X=2o9sG+y%q+tME~n5ly{i7$9V!ANyl|u@cVHHHm1d~vRVi{|bHpBYl6KGv=?{4ETQ+F|rTLx&my-hm{W0QLE|3 zKh3SA`|+Db(*EFlu{SUZrEF-@v**ZaPm`*L?uTX%tJm&F`^JGA11UOxo<9T(d3-hU zHxhGvRFn1yq|V9ItJ;Rf(hdJ3-(%;K7J|Vd!0sU2gB&+BsZr=bA%7bB(o3xm%Jt|k z_2@6Z2E9c{@)~J@%K~moAanr#eqf`8`$sJN9FPu1jfE-J+awJjP6Dur}#Z1zF zr!j)>Jj_sg}(te=QH(qnb>dp$0pmlOs8*JQu12l&A5CZN`_)Pdzv7~hzO}D?VSc-`g%W;%pZm5ns}17hV65Kd{Hih}9cPO7On~S`*C5+m_gqB+BEXqzXJ^=s4HK8*1#4 zt~U8Ju%;-zSdsuK2hY^X5opW0D$TKUxj{Z+%|3TguD3VH z(XNZ&)S2XpnVWv!hF%Z~Zb6Urk5H!Q{5&BD>YcEY)@i{K`3GF>IZKdKC?QBMWLaU2cHS7qb1C zDrtL0@ie-2mh$Zu^uKQvdRr5unlGw*EUHVal-5k8R$yB^p*0Q~e198E=;V7w2`GE? zl2X>&;(Vz`)S%3RcPrvU$4d2WnzKt_e?&RHtK6n?XSc&52zfjUJ)9IxcLbCsSn+x6 zb(STuoHChgU0LK}C1MA-Zru^W>#ZU@r3fWUOCLM;8m^gnk-H3KB#nwYJbSE8@YqHt z36iIaf9D-VJVjI_?>-}ctmutvB8Z#~4~C!FC2` zR8#AqrbmoM+wxPT3aQ_JpE6bkR)sr9x?hUwj?|vVJiOCB+;txLp0THv>@6K@&uKs0 zEeJ0qHrxSwHt?w_N5N*1R-w-%4L;?iGS<0S&Sv-C($CHw>y8u*?s?K-XxsKCRKg~i z+0yNmR2JA?Fk3v8CI6(iT>8KZpAEQEU|VHh;k{p4?xhm`Yaqo_xHWt3Vl0nZN>rXYZ?5GP#j|-3QgZ59K$P4TmV z-ZYmVD~wB*qvd2+Dwf-QEphTuS3S@RM?U^~snUL@465N2aIQ0NYvzoL?9Xj9*uj9tQ%Hn|ey#(>jji9~B)CZ=>8aQtqj zDQb!>C!aPBS3g$T1FqM$hrJc)+(+bESYis0MC+NZ(=6Fmne4TzDuJwt_Q0G^lu}Tw zPf^n?@PC9^@+Y(v+FbCn1Da0QB0%dq`KaL3USLM!ikmV=W-_kOVmEE73;6#daJ=8h zNY~0@y+ZT}>sIq8iol4T_fbd~9dL*D2k(Q@h=Bg+4ZkJ4KhMWn2X6$!@hubOw*Lj) zFkF_%3&IwnGzBL!ibGxk48(O{iuzWv=c9Hadhws%Q#AU2;{!1B1kwrp2@Nh`%dG36 zb;*$ZYKOGA*7&x8#>89I76_Lj>ND~SH{F%=&}OoWO;3=LRs{TS5BVNoM$#M{$u6NR zPY;!a>P()Au*&!UuqO(yt^NL26_n;DK#1f9XcZbe@5}=QHqJ1$=WOSKseni``Ja z|4~phB}k=bi(Ivj3qZIb?@>gd^Z2KD2edAKx_9>be~p>xyQ2qOn;+N1Vt?zotPbRM#KcQ`4 zL;V84?-(7`;Di!=HAdmFtcIM-a%(PQpn!tTJT%Oq6U>)(rENmGxbW%Tw>)a_nXKm=_1X^oe>eg^O?caH{@Q}xR=E2wP zVf_V_2B;y-dH;E8;xm5a#R=GA_KlL;r|@Uz(*# zQFer|Gon)EUQx%K9^3&h@B|F#tD6zm>$RnFIa9Dl(6@pS=k~9{9wR*dMrz*i0+%g=+JT+fH{H=x0zE|@nkr)XSEIzTOF_O= zH^-O&szxa7<~Ys=34p3i2&^rnpNX+Z;}Iiu-HxGg8*S&yZ8l~k3x0~z!$RrNbq?s2 zrDC09Ch~2~`5Mt)MmxoTe`Vr)hZLb4Sjs`cv>Ye`^iAm5{H9^DMtj|76F;1#rIu-WGDP&w z&Ql4WE7hlx=M;BC3S{~=7=yMQtC+CU95sjNr7N^kPV4uVg)Dee`QUElUIR0Y$!b^; zhyB3~f3mX0g?n~3{sZ@7v>u9c?cmZc>L)Bn;;CteC@VutC1#Bt zPr$ne>2@H!h_%xjIsoofg|(tsgl0)3P#0pP^lCnvN}CrXZAh($Jb%*63VHZR2l&$T zE=c(1nn1Coy2-D+cKSYRVtZ^kboY8#rErZwcYQcy3#gn6H^`=DtZ=@8 z{z;|=yP<{Z^EArDm$%u^!(+$|Sku!z?5ltpVW@qkk!8N|GoAFgA~rxe;g=y2FWz6CO0!9`E=0k&_d_G7khBd z_lJJ%{Lz9oyi-w(map#fb%^Az6R%e5%Zb!A=@IoMN^M9wQ&2BtCO37v$ij}I^I#-8z=B-xJ(n@(4*Bio-QdBCMp$RWEEV6v?4)zo`X08`_7w@WeS)plXB4<1 zcp9BJ7dEjj)Wz#T%cMcaa5^{fR~AiH$5BGKsl7aET%SiXncDa@>&I>Qa))%!hy0m? zR2R7E`I^>Z7|iT=*GuDw#zXZhOne&WJ8;n4usa?H?$h|C@u7PSD^2uhX@!x8M$bj? zeNXkCc0%qL&F?=6dw8;#^m%mqc{TnU#KVV-li#0!H@zRaN7C&en()hkSnq$&sYT7H z;eXBPT{WkAzf=3r=Jq4 zD4p5&?4Qx69FWFa{x z5;HAB4Rp}wVZNx)Z>*QxXJNY=SMWp5;|DQ=FRZ=T{V6W8 zT-OBdv^lyXTtDUu1~{`utzCG}g!I51qqL-{ASIw5JQ6woI1raehapWWLhJmFo^f-x zvGLbDT%nKVp+^GhGei}v3S!R-oeZ%_oD*vl%f;DA(6C!#SNs$DfjOTZYfQ3}2PD7W z{Z?q9j*aMKoi*E0W`y*7u-_t!ErhrvG?&>$P=*3D0EbI)a-53X#Cd{#-y4MOlz=$1 zD-HX9vZsv3741_%n@AH~+*CfR5Zd*358)QY92c5|At?ehI22yRDk7PI{`eEH0AB0j zB<>LNS(V5m;$EEX3i>bK(5b0Z6gR|`DL${G>FLH1paUZ$%^?A3K({ODpiwo4g8p+i zB7p2>fb0u?+JN70ryTcTHl+RJJ{rkE|JyeT?RxA4sFefWTA8l`KF-;9WY1!jRx7^) zilo-=Sxo*if$L+}mh;POkT#v_;wMHsh@bM8r^EO^wQ5R220|;9Q<_@Tp0#!j#lwy| z4LrINQy>N9cCcMLj#1sP!`;vJjjkR)o^$7nhfRI~SDz+vd!YNEj2|ECY3yP1Bin=i z)BWitvPx!_$C^iWvdnM20q{$}voLGV2mQ@z>>9+*a7}h$Kc{fHN31{!m~OJuP62d_ z?a4;iyVIM^3*7YPSMlaC)#LN<-n<0$y_~uelAyg2hdiI{XBmW9wffi;7e|OVxo@aB zlErv|J-w5S`x;hsp(2)XB6v;F2F3n0mm?#&{lbwfDWMvgV@idqq*Q1V_8UBVOJk7Z z12pmrsUG9=&Usc?*@Uwmk}?vdtqE!ix&2i83tsqbhel)2qnG}LZ;PFlyrbDvoe#i_ z%IXJF1fbAVy0vYc?+?Aeho{vsL%4usTcAl)>xA}4ge#FGx9Ft7-nR}e@54lIak~5X6=Q$kRl2x z?iRlDT5x?Uu6bNf5g<7+B}kW0PK~6MCxGV2N11^1X;wUAQ6g|ccLe>@f?WQf|0w+6 z7~oYl=!ZudiRLzL4rnaMtr{_R;Tshb(gD&mpK*=1%7Ztdct~3-N`kG)aOT@~g35Xe z#>-S_Zlo*xc-Yop*8$Ik3N&o7R@JChTF@dqAvOj5z-q$SH=4EX$RdsT=^-l^;wnZV z?Y6bp<(^>amfn%b``#0Zsv|H=8YQy{#qNSCTk|Wu(GxXUw?l7`^XYFhn)4VeVREjz zr$P6C?C7qzl@=cFzuz@oE=P&F6d)k;k+?&)NzC`f36iWEaj(zIspV`#3XT`kz8kuB zBbMW@d#?`3M@2XJZw)`a`~+zRkX$5zo$>y7#tHck!v+aFscxEaVvhf^N%tr2Fg)q3 zV!s>kKMN^kLa^ z5Ci`EK_UF00r6k|Ljxk<|Jx8Zfi#f9xMj^QL$e6YHL;V)MX;Gp;D|!o4!`hb)yv7Z zpy02b@Aqm{{?8Li7ivvj7+LF9tUt9_V<);}vnHuuLW~|gv2en~iH0!~3lU}wm$5#c z5a8d!iT>=E1x^%p3S&IHoanOlIhXVHtKM{k=v(p?Z=5VZlH=x0J~uS~1k80`;+~~9 zc4Ejs4>PIt;+Vm*d#c1J?B#2%9 zvecXe==nfD$}A;0iU{c}=eqY-&Fh+3)?4V$m{p4-I>lCIPC?mOG0hXq*WUc69#Q{r zm*)SltjG?QlLTq%!^#Ck(~0t!2vN^sC3GB?lZ+Vqk7C027g{U3ZGvM~I0PN|KT`Y< zSNx;6o6jw3o`dp*ONA0m443M+Ka>jmh98&a#qXk56@NPlI3UqW#{re&%_|?QI&noR zfB8!3uWnrV&tKhg#gH`W%8n>?%>o_=Q-8kOhQeZ!8H&HxNKXUh&*H0fZnKV(X0;y; zZ0@zX-sv&2i~#fPv^;OIT;}wh1fCicgSWhGyUf`lf-yaNtyr%T zB6>pkPG4fpUaO_|mKy%{=_N~(UOsv(sQAR7p`hfl0G?LN;H#yP?K2V?WCTv1w&vAR zOD|u;7tJWKT#m53+#RD~V@JFGZc%lkY!hjAdx~!k{TG#qWiRl2l#EjR4DVOCvB!dg zH`4Sm!IT2{Lns!5`m5Wmy7o;8dX$4dOZ&PmXPxw6Qo~VKaL^YMGz>?1OT-{k4wUMK z%D|sJ04ZWS_6;w0iyF&iy`|N=9kpTOna>3;70}Iq1x2_V#{#w2*@QWs?N3?-mVBF_M;WNyl$hWxR1UP8h<4Ki z_`adGo8k05KHs4Cwt_AmZx$%Oif47SQ*Mu}!BE^p6SDp#+Ikg5t=a7}!?I2O@eIQi|=% z5?~FUUv_p|snmYB2h(xMOWjdi>-ViU>oPYBrBF_w^}O^2Cr&tfqBIw!7>BPHX#u8? z?m&>=I=}P-AYmk(8|A*wb*wvv|3x>a(*^W5dM$H-2IaS)oyM`T;WnKhnWbppO?G{q zAPszNEB)&1iEcio3S4cj=yR_qo%PzKXS_91v-bh%5pO=QiC*vF^;1jYz0_wiFwarn z)?sBbG+B+}+<<@l4UFwdo6%$sK;N^(81QGn3xzPp1jKB0{{g>kZ8%^nioL*5(89FG z>X0jJ%=cnH>2A@S!hB88C80eq(ZZkLeiO8mnQtHd!|_|2L*MGj&kfcg@^iBgK4~H$ z3mJ}cadx`z(8BaSc%*|LE4qVu6z5b{hIboqFc#u+)pDS`cJTKD^L?C3kuz|#=&dJ$ z;TYqOVv^o~*2Wu<>#2E(-?7eESgFqM1BVH1U`vh3!Jb3XwK3n!fDu|CVSSpP5r?b? zZ@Gqaz9T1Vbz094*B4bhMtc6HypS2#y{7VvIX+cdI%>NB-LmVTE!^3md6Y?G`;x3!l;n2M0DQ{2Vswb;5Ob9rjCv>`RBq~1E}Ec8~_ zRHQuKoSU)Pn&RNv_oUqCuq62))%(?GtfejLO=?Nk37l!TfEpr z@zHLvB@*%1f=qsxU%d1U%Uk$ zW4MNY_B7J{x(>Wp9@wNw&}63j36$4R+B?2a3+pjFJA3F_V-8aR@oiM|vjf8TNbv3$ z)3;^-lY^x#QZn-sZQAlgv;}xb#v*kW81%k}@>6}WrqB?r@8|Ka{ZyE<1U}uiOtQ&K&<-Z< z7o}qPK6u}aYU8i5xXspxcI}*<(5`wK+!mtLY4owy<7ki5IE=@KNfvoHbaTxmpjMY& z_n&V8_cUFPGWDo-6k3T&AkJL{d$D-f4v649p%?hf0d7X0hcq3FS`wri=�?bdbHO zHgwRo8}!eEKB7j|%6l28@jJkeBnf|%Cw+n> z;=RM5S)eqovuvKV=Mm^e(t{1>hX85^qe&KsY)G`tr zX&{1xEH3Re20MU|KOqB0G`R8iC@Bav2on&B2uC2)BQzj1Ak-rq zflx%4fKY=lCI4nVl>c7`H>1vbVJ8y_G$QJgr`E)~p<4@`0{T|Z4N_?qN+Z-S5XP=} zPA${?(Br@fG>Y}aSx{?1`8__EE#HOm?XzZk9>iG+&N4kmaF&2GqvtZtM&K;jlU;Qe z%DK;ai|0X{>2WsPa|CB1&h(zkIMd)vhmsj@4VR1a7$>jB*VE`8R==UeYfcZP1^fx{ z`ly{tZ}*2ZJ!Tg2UxgJ#C8&nu*sGI#i35`I9g0|Pk-5T`Svpb{-KevIUN;(AM$a+& z#t4R{#qtZlcKG{)4b}_~XEH-eTQHrvx>*z7JmciZa`*BB@V8)7jD|6uzUCxZm!0g{ z_aOLHZlTAlp?7~0BJEAIMIr2a(SNaWn>xU8_{^(?MCL8@Ewb-;HPquxv9pXTUMkyX zIEtD^VBQ_WYvp_7oz^6G`-9scqu|ob8F)L3O49`SLN3VjFIf2=o`)69f(W+`JV$zG zeaPtg&PF=iEd6W9PD1{T7`B*?kgu+(+7&tHriKUjphG$ykO1#UgpCT#6+hPV=pDr} zmaThun2aohAai@b-ty`OivXXe+Vh72D<+ z5m&YBA>)d5RU22X`yuI2X40~%hgPmIZdhZiM6MfF8aK!*|Hq>%H&#`yoMy~i@x$Yb z9;vKcxqkfvk396yCgZxH*HT75@%Yf2^H!|fn73iWrbX2(gsQ3SkMJjd%gm5N;6#ve?OaviTO-?7x!Cm?978~ z6XD*86c1WigG0oj$6>&6^Oy3&`6S$Od8@IdBRrbl?{gYj$_!p>hz zW-$m^L* z2X`mkN8vXc%f?Y?y#GLNF+#TTlNL3s`{z??=#E>YhA593vIoDhP&&5dSU9vi5f0hx zp>Tv{-(LDP&-~ShKhOH&(Yl%AZ7JOsZ%vvx?dklBzui=N`zkmMezlm=w&9tp~eT6yVG&Mhd85T8Q_k_bO@2X+lKc6oS*R$9* zYPGhh=|sJBt$${hFu!Qtq|y2PWxw3KWJc@yCoaq%`N+eInfR|I(A`?Z#82)T>TBpp z#dn6!Z}xW#!ps$D!apsCPsC+RJiLO54G7o%oQcbD90nG`NgORWo_PSWd4yE9lfV$5 zkbYBd?QjY)WCl`1KD}JO!`aJ&8nH$GWi)?g%7kYwIWBz~s za=8lq%{c_4EQ)1(`I1`ppPpBQq55JRO{VN)#_7oSdE{e}EDA>j=<^Ne6!iWuu52i@ s{YS;<94gphq??KR3oxGlI&@A^YP69p#Oe3#s@_YZdj?Ux>16Ex0*ChS5dZ)H literal 0 HcmV?d00001 diff --git a/boards/matek/h743-mini/firmware.prototype b/boards/matek/h743-mini/firmware.prototype new file mode 100644 index 0000000000..d715678889 --- /dev/null +++ b/boards/matek/h743-mini/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1013, + "magic": "PX4FWv1", + "description": "Firmware for the MatekH743-slim board", + "image": "", + "build_time": 0, + "summary": "MatekH743-mini", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/matek/h743-mini/init/rc.board_extras b/boards/matek/h743-mini/init/rc.board_extras new file mode 100644 index 0000000000..a39b81bdc2 --- /dev/null +++ b/boards/matek/h743-mini/init/rc.board_extras @@ -0,0 +1,16 @@ +#!/bin/sh +# +# board specific extras init +#------------------------------------------------------------------------------ + +# if ! param compare OSD_ATXXXX_CFG 0 +# then +# atxxxx start -s +# fi + +atxxxx start -s + + +# DShot telemetry is always on UART7 +# dshot telemetry /dev/ttyS5 + diff --git a/boards/matek/h743-mini/init/rc.board_sensors b/boards/matek/h743-mini/init/rc.board_sensors new file mode 100644 index 0000000000..c37c3b3b58 --- /dev/null +++ b/boards/matek/h743-mini/init/rc.board_sensors @@ -0,0 +1,22 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ + +board_adc start + +# Internal SPI bus ICM-42605 +if ! icm42605 -R 14 -s start +then + # internal SPI bus ICM-20602 + icm20602 -R 12 -s start +fi + +# Internal SPI bus MPU-6000 +mpu6000 -R 12 -s start + +# Internal baro +dps310 -I start -a 118 + +# External mag +qmc5883l -X start -a 13 diff --git a/boards/matek/h743-mini/nuttx-config/Kconfig b/boards/matek/h743-mini/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/matek/h743-mini/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/matek/h743-mini/nuttx-config/bootloader/defconfig b/boards/matek/h743-mini/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..ae0dd4e10d --- /dev/null +++ b/boards/matek/h743-mini/nuttx-config/bootloader/defconfig @@ -0,0 +1,93 @@ +# +# 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/matek/h743-slim/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_PRODUCTID=0x004b +CONFIG_CDCACM_PRODUCTSTR="Matek H743-slim" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3162 +CONFIG_CDCACM_VENDORSTR="Matek" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_PTHREAD=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_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_LIB_BOARDCTL=y +CONFIG_FS_PROCFS_MAX_TASKS=8 +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_SDCLONE_DISABLE=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_USART1=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="bootloader_main" diff --git a/boards/matek/h743-mini/nuttx-config/include/board.h b/boards/matek/h743-mini/nuttx-config/include/board.h new file mode 100644 index 0000000000..f322c3cbe9 --- /dev/null +++ b/boards/matek/h743-mini/nuttx-config/include/board.h @@ -0,0 +1,493 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6u/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * 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. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H + +/************************************************************************************ + * 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 MatekH743-Slim board provides the following clock sources: + * + * X1: 8 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 64 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_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 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 480kHz, 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 board has two, LED_GREEN a Green LED and LED_BLUE a Blue 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_BLUE BOARD_LED1 +#define BOARD_LED_GREEN 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_3 /* PB8 */ +#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_1 /* PE9 */ +#define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ + +/* SPI + * + * SPI1 is MPU6000 + * SPI2 is MAX7456 + * SPI3 is extern with PD4 and PE2 as CS + * SPI4 is ICM20602 + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_4) /* PB13 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */ +#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#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) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) + +/* SDMMC1 + * + * SDMMC1_D0 PC8 + * SDMMC1_D1 PC9 + * SDMMC1_D2 PC10 + * SDMMC1_D3 PC11 + * SDMMC1_CK PC12 + * SDMMC1_CMD PD2 + */ + +// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */ +// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */ +// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */ +// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */ +// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */ +// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */ diff --git a/boards/matek/h743-mini/nuttx-config/include/board_dma_map.h b/boards/matek/h743-mini/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..693132c389 --- /dev/null +++ b/boards/matek/h743-mini/nuttx-config/include/board_dma_map.h @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * Copyright (c) 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. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + + +// DMAMUX2 +#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */ +#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */ diff --git a/boards/matek/h743-mini/nuttx-config/nsh/defconfig b/boards/matek/h743-mini/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..9266990f21 --- /dev/null +++ b/boards/matek/h743-mini/nuttx-config/nsh/defconfig @@ -0,0 +1,226 @@ +# +# 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_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_TIME is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/h743-mini/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_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_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="MatekH743-slim" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="PX4" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=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_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MKFATFS_BUFFER_ALIGMENT=32 +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +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_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_NNESTPRIO=8 +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_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_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=2048 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=2048 +CONFIG_STM32H7_SPI_DMA=y +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM15=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM2=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=600 +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_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y diff --git a/boards/matek/h743-mini/nuttx-config/scripts/bootloader_script.ld b/boards/matek/h743-mini/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..511ef26242 --- /dev/null +++ b/boards/matek/h743-mini/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * 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 Durandal-v1 uses an STM32H743II 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 STM32H743II, 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 Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI 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 (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + 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/matek/h743-mini/nuttx-config/scripts/script.ld b/boards/matek/h743-mini/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..580f63f0a6 --- /dev/null +++ b/boards/matek/h743-mini/nuttx-config/scripts/script.ld @@ -0,0 +1,222 @@ +/**************************************************************************** + * 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 Durandal-v1 uses an STM32H743II 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 STM32H743II, 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 Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI 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 (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + 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 + + /* 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/matek/h743-mini/src/CMakeLists.txt b/boards/matek/h743-mini/src/CMakeLists.txt new file mode 100644 index 0000000000..f677ccf9e0 --- /dev/null +++ b/boards/matek/h743-mini/src/CMakeLists.txt @@ -0,0 +1,67 @@ +############################################################################ +# +# Copyright (c) 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + 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 + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/matek/h743-mini/src/board_config.h b/boards/matek/h743-mini/src/board_config.h new file mode 100644 index 0000000000..01d899a7f7 --- /dev/null +++ b/boards/matek/h743-mini/src/board_config.h @@ -0,0 +1,237 @@ +/**************************************************************************** + * + * Copyright (c) 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 board_config.h + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +// #define FLASH_BASED_PARAMS + + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +#define GPIO_nLED_BLUE /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +#define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_ARMED_STATE_LED 1 // Green LED +#define BOARD_OVERLOAD_LED 0 // Blue LED + + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ +#define ADC1_CH(n) (n) + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +#define PX4_ADC_GPIO \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* PC1 */ GPIO_ADC123_INP11, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PA7 */ GPIO_ADC12_INP7, \ + /* PC4 */ GPIO_ADC12_INP4, \ + /* PC5 */ GPIO_ADC12_INP8 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11) +#define ADC_BATTERY2_VOLTAGE_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_BATTERY2_CURRENT_CHANNEL /* PA7 */ ADC1_CH(7) +#define ADC_AIRSPEED_IN_CHANNEL /* PC4 */ ADC1_CH(4) +#define ADC_RSSI_IN_CHANNEL /* PC5 */ ADC1_CH(8) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY2_CURRENT_CHANNEL) | \ + (1 << ADC_AIRSPEED_IN_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL)) + + +/* Define Battery 1 Voltage Divider and A per V + */ + +#define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +#define BOARD_BATTERY1_A_PER_V (40.0f) +#define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + + +/* CAN Silence + * + * Silent mode control \ ESC Mux select + */ + +#define GPIO_CAN1_SILENT_S0 /* PD3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN3) + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 10 +#define DIRECT_INPUT_TIMER_CHANNELS 10 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + + +/* Spare GPIO */ + +// #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) +// #define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) +// #define GPIO_PG15 /* PG15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN15) + + +/* Tone alarm output */ + +#define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) + +// #define TONE_ALARM_TIMER 2 /* Timer 2 */ +// #define TONE_ALARM_CHANNEL 1 /* PA15 GPIO_TIM2_CH1OUT_2 */ +// #define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +// #define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2 + + +/* USB OTG FS + * + * PE2 OTG_FS_VBUS VBUS sensing + */ + +#define GPIO_OTGFS_VBUS /* PE2 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN2) + + +/* High-resolution timer */ +#define HRT_TIMER 2 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */ + + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS4" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5) + + +/* SD Card */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_nLED_BLUE, \ + GPIO_nLED_GREEN, \ + GPIO_TONE_ALARM_IDLE, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 4 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/matek/h743-mini/src/bootloader_main.c b/boards/matek/h743-mini/src/bootloader_main.c new file mode 100644 index 0000000000..5670308a29 --- /dev/null +++ b/boards/matek/h743-mini/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 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/matek/h743-mini/src/hw_config.h b/boards/matek/h743-mini/src/hw_config.h new file mode 100644 index 0000000000..f289dc960d --- /dev/null +++ b/boards/matek/h743-mini/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 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. + * + ****************************************************************************/ + +#pragma once + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 139 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 8 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#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 diff --git a/boards/matek/h743-mini/src/i2c.cpp b/boards/matek/h743-mini/src/i2c.cpp new file mode 100644 index 0000000000..1444ea1172 --- /dev/null +++ b/boards/matek/h743-mini/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 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 + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusInternal(2), +}; diff --git a/boards/matek/h743-mini/src/init.c b/boards/matek/h743-mini/src/init.c new file mode 100644 index 0000000000..bb1c6f975c --- /dev/null +++ b/boards/matek/h743-mini/src/init.c @@ -0,0 +1,182 @@ +/**************************************************************************** + * + * Copyright (c) 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 init.c + * + * FMU-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. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +__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) +{ + UNUSED(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))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * 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) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* 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; + * + * 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) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + return ret; + } + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/matek/h743-mini/src/led.c b/boards/matek/h743-mini/src/led.c new file mode 100644 index 0000000000..2d60d89be9 --- /dev/null +++ b/boards/matek/h743-mini/src/led.c @@ -0,0 +1,112 @@ +/**************************************************************************** + * + * Copyright (c) 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 led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE (defaulted to an output) + GPIO_nLED_GREEN +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/matek/h743-mini/src/sdio.c b/boards/matek/h743-mini/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/matek/h743-mini/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/matek/h743-mini/src/spi.cpp b/boards/matek/h743-mini/src/spi.cpp new file mode 100644 index 0000000000..db673bedf0 --- /dev/null +++ b/boards/matek/h743-mini/src/spi.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (C) 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_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortC, GPIO::Pin15}, SPI::DRDY{GPIO::PortB, GPIO::Pin2}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}), + }), + initSPIBusExternal(SPI::Bus::SPI3, { + initSPIConfigExternal(SPI::CS{GPIO::PortD, GPIO::Pin4}), + initSPIConfigExternal(SPI::CS{GPIO::PortE, GPIO::Pin2}), + }), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42605, SPI::CS{GPIO::PortC, GPIO::Pin13}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortE, GPIO::Pin11}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/matek/h743-mini/src/timer_config.cpp b/boards/matek/h743-mini/src/timer_config.cpp new file mode 100644 index 0000000000..6d68b94f69 --- /dev/null +++ b/boards/matek/h743-mini/src/timer_config.cpp @@ -0,0 +1,82 @@ +/**************************************************************************** + * + * Copyright (C) 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 + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}), + initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}), + // initIOTimer(Timer::Timer15), +}; + +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::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), + // initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}), + // initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); + + + +constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = { + initIOTimer(Timer::Timer1), +}; + +// #define CCER_C1_NUM_BITS 4 +// #define POLARITY(c) (GTIM_CCER_CC1P << (((c)-1) * CCER_C1_NUM_BITS)) +// #define DRIVE_TYPE(p) ((p)|GPIO_OPENDRAIN|GPIO_PULLUP) + +// static inline constexpr timer_io_channels_t initIOTimerChannelLED(const io_timers_t io_timers_conf[MAX_LED_TIMERS], +// Timer::TimerChannel timer, GPIO::GPIOPin pin, int ui_polarity) +// { +// timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, timer, pin); +// ret.gpio_out = DRIVE_TYPE(ret.gpio_out); +// ret.masks = POLARITY(ui_polarity); +// return ret; +// } + +// constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { +// initIOTimerChannelLED(led_pwm_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}, 1), +// }; diff --git a/boards/matek/h743-mini/src/usb.c b/boards/matek/h743-mini/src/usb.c new file mode 100644 index 0000000000..4fdfafd250 --- /dev/null +++ b/boards/matek/h743-mini/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 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 usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the 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_STM32F7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/boards/matek/h743/bootloader.px4board b/boards/matek/h743/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/matek/h743/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/matek/h743/default.px4board b/boards/matek/h743/default.px4board new file mode 100644 index 0000000000..a6af641ec0 --- /dev/null +++ b/boards/matek/h743/default.px4board @@ -0,0 +1,74 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_OSD=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_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL_L1=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_LOCAL_POSITION_ESTIMATOR=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_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +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_DMESG=y +CONFIG_SYSTEMCMDS_ESC_CALIB=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_MIXER=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_PWM=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/matek/h743/extras/matek_h743_bootloader.bin b/boards/matek/h743/extras/matek_h743_bootloader.bin new file mode 100644 index 0000000000000000000000000000000000000000..9a03d6bfa45a72833640a48bc26eafb524d3c1be GIT binary patch literal 42684 zcmeFZd3;pW{Xcxpy?2%@kV(Q4l0aq&kPVz9pb=b#ndD{}G%RWnY@HCq8)6{>+E8g2 z2x?@pKxhj@E0Wr(SY-n7YtWb|YHO|S3`@U2P@_;UBq(=CU~blV-e(4EtMqyOp8uXd ze)D>rx%ZxX_VYQP{c|smC8-m6qJM?^zv=(3!T*0?fL!|pFTTIy$G^~gc&SI@o}dUZ zocB^s#QLq`GLiF3+@+q_+9}@{Hch!OSXv=IB7ULH@e)PXZxZY5@m}J8gnG^^F`kQt z$nEE&36)G2qKWAnL!{|~5_91EVClAthE05@2X`p5iM1cyw!TMSx4tK$uC^z(uBxz; zBdPl4loDb}an{?jk4G&C`o;ndPdbc6oIep8C9255-;t$@{g4k#pZZl zeJwj)a`aa5@h+m2_qFwu{<5uS#V_Mg#-dQ<&JSJZyRN^X%I0CBjO-_hZP1|#Nq?5- zsX`R)qW&xkqe*HfA*ooB)XtZP{tT|uE|Jb{NcTH897vSRy>7F;*PWB-y03)ppnFIL z>3P9T8%U?NlcCrWnZ<#~y&L}>>dJdr3F@IMXn+)V~g z%*559XwlZKPL%7l*+b=o!4o$ZM@rjposO$r;kZcGw9p;J9a_ShY^T|r=(3`oSr#__tFI7;jEZ6vygTabVxAob#XmOvH|BbjHw{XIwvkmexi zn@vt?B1X1y6tkL85{qO&8Ye~CCKTHh19HbBH@vfnu7ssTajU_AK9~?%QG%UgP&5Xs zljxeS>a!e347wbOd%i8Kh5M68XOKFP&Lb&E=a8xjgBPubaOO4=i`#su$56ZS%?&suwLOM92FIhFV@i^w z*gC$~{aCe!X2-hY>K^kP_7Dqud#-6C%I^0FM(aC7dEl*L554spnPgn@I(pr!v?cK_ zYUz^66xnORGl%D|Wa~Rsg%~H+lbu8Kya7F%!ac9Q*0Z*l!LoZ*l#7@I=Q#JVCU$az zfmgq)r#9vDgt#!ay7o}&L zA|0HIwQFtNaDbQ#E|--ZxbpLLQ74Jnc6A?Jk`{}*$g~9fleZc4;1o7&wsW8Dz4G&_ z3o>n>xwQU@9L}YmEy?@mwY;mLyfc~fv&g*9|08cS@@U@wewP=#cpX=0odhQXD+UZh za^t_lA#APY04I$4hIGcH8Je>{+v_(7DOr(cc)!cRUnz4$VU78Ip?8#v7?V5i%+jAs zo^8!b&W{e|6UE@VEI*hfoJ^QKCzRVGufx;m*;S#Zi}J6sxKpJ{&}wLnoxLrT_mymL z3TaU;-dEb|##oNZnlujgBv+NSp*y#wM~+E5>(e<|@7VD+;Y-q~M~X%=Af;lwhECEs z-pSe?Uu&r+7#KxP3CZnh8j#yZCqC(It_Dphcr%S^7_W%KFilJM-7 zIPAci^(YmK^@%NxGA3fTxAqfrOfhdHN?pGN_-viSp>#SdF2%xjbMc!7?7x7%-E2%4 z2XL%DnO)D3P6ijxM-crQr1)mHg}z!L3SuxYH)w2$$@=U9$>u&A=i&|+T5(Rh*hyC9 z_-685x!Z40F4B?c>XWMq^$gx>$q&xa(6D(<@ z?TsGdCe8E^Q3RE~Lt4YnLWZk@DE!E>p4yQ=cOE-GQepYmQ>;p75~O{8%Kf+dDHoKK zvfmBg_-iaR=j-SN2N_3TcEI~}9hY7FjTTF)yf9B2c{00M5kK0-ROz>ch$Acb4yKPns}RQtt;8}fa`AO zzy9wE-G~2qrDTw|B$!KzZQ}mNOPsH*|L}s4tF`Q}<&|d#3!S&3jVD#ttPj;C*+(vr zjl6Qc-|nQZNaA=GXPGrSw~8u`ew;0;RgMh^7K_Uw(abrY8KrijRXPWV`BrD?)!^E( zVuH&kjgz+73(lA&k~+ebBuy%M&YixFD2{>DBC1^OPcWHr{b*pn)FAP$6r8I$xTogC zN7J3jZr+kxrBPlSp6rbB5ao%1Nw`v_p>HCtTIIFj)KLD%L8|<*U$Dd!Q%k4Hw8NmFW8A6@cZ zMwHA`t=2^zuDhL^C+#ZKg6BYTf#Wc1oLA*Uk=0@4*;=sqvikoGALard1_Q4Ruf}*a zPD69Dl!aZI)^BJzyP4*mt!227wUgI8%9$+v74IhXA85gRp8O$hJ=8bBN-`tP5X;%x z2xpQszvY`IM(2q!ua(YhXhLh5SA3UbszmquF-F!d+q0_Xrw#}r&O+5l@zV=Jj#fF; zuMz+3iQfHGEw?>tH{Bk&`!nQ|?I!RQ(^O%C=5(5UY4KvD$eDtH_RyR7X5m^c zF$V+PLAKjdF7y;?*VTy{al4o;rih=ZX?uzCL7y-ozk~J9Yk}$eg$a2bKl98J*~z2I z6L`+)NHDScTl?!;*m%-9bHqr00%du982zQw`z!f_*`e}{eMz1BrDD-g!p=~d7}Y?2 z&1jG?VMIsto>?eEluuOlzpqaaZ5~~5n#d~=edMMyUY7epAA?L_wWmqjsW_r%@D5yB z`Xp8qvybEJufg8;_{lHSyzNNq|01@4-Vx(Tl^mcsg{5&#w@WYEM|9*#3`3mkvlnYb zl6IHxY7>J>%!b%HX~yl+TW!=#Zy#+d?fNh}s{6x{i`40J$du{6zp2D_wF#|RUq!pm z<-ev1#(nEqU9N#QKCk8(EoFQIqbSd-f}y;uakJ@hi*kf7dpuo?cL@G`uCW$p9XO67dVsz*;r)$P5=Tj}`UO z2764${UR~OmClg#*P$3%53z`i}y_h*&N*&r7Hmt?6qoiyibv_Y-eeZpVq zjJc}*w&*U7({#TdjS?(3i_PM+%O?(=dm{$(>iOB_TXNlajJW<=dky0hAPYWuxF@mHyyrerK@)f^6;-Dzp z-VWky!(3m)UVHLqiFDc=JniVaC;wDIqK_C$R3Z9L>XI@(G=JM=I__Q-Vr!bu%PUX! zQR@?x+WgDX#>H@ikXo>w&&#W32?)&`r$?AFV3PYu+en#A%-LH8fK=MQ4^j zN-XKEZD!8f7`ggcgQbtIff0Wi~F1%BoR*j5lmNM0xY=f91~mE_eUi#G)*c48^3tiJe9Im&Ns$hcx@<{DNLnOHEKc%ggGNzpHA%}JVch&B z*(`kns2eR@yhaNWoYv;?(vt^p#s?pHgkiUr2hTYK8^1FZl=5BF)*P_5@-GvmN_8Yt z(cq=q_?J25>@eNUO2-2VtR6a^-8TSIh%!~>p`-aH*87D)YW(6_KY7iyQiy_?-9|{G zn1lP;9EkCOiq#(TnoV}CkN1zF))qZ>-aIUH8pTw}FLTPI;V?}zig~SuX8wshMrn%P8zHr!)^Gw6Jp31DEAs;5Wfu8MI^82r;5s5YrFlTRBA>rfE8{hK-+bFyF%n zjWt)Bw3%_f^lHIhL^$Q9VV5TpSmEqLm6ByCu{16r%F*EvKQrlIC%gVmO0Py+493~o zL&L$=o@qGBE8;x~YwGNJ-_a(f^~m*PK)13?+T-e!lOzT6xGK)f@060(SA6CQdO9F;3)d`Ns3O6Z{vaOdSf1H0^}XVALoJhe=wa z7iVSFr&yau2hywe0zW-5pcQQgZBp7nqC7o7(wyE^=)XzY;OdbYw8HW9YHHbRi+9wz zGNmIJ7hiVc9tHnw%KAJ$7+#%V;O+sGtoz{_CxZF`{|zela%$qe%fPlV~r-0_X#G}#+AOt8eQfkUuLyF^P-RCyw`UgXW}}{`4Wg; z*G#t)<&nNL58cfl_^~Q<2Lo5$T>gvviHT!{0?XcAAPZQ7NGI& z!Q*QFfo93srO`aJgw9vFiIMqW_e z?jQ;UUZuHFnSM~bs={5Msd>#$N(-T>OJt?Vdi%IgX^lUbJRrRj!XZE0dG_`kU}V)G z)9jJd_)ga5=RTQ1@eN>|Q|1o-3pfeAi5M}z{bqaFh@z&yOYkl;Qs5+XP)D-0=7Jf;1l#H(lwQ3G=5;!jm`?2$~p+=Jt z;nO^lQAcy)nljwPOgD1C(!qgnUwN&;iz;N>G-vwVE+aGu`Dsq}Kl$4KN4RIt8s#qo z8nMVj{4QPAV`*Z-^lZS)Py64n2Yl^V^S1{W??(LX8gBB~yC*+p6ceVg5)bshgc3HC zc=cKdn}$p_+&y^}IF3*WXQ+gm?cuc&ZnUBQw-Pf#CDhixf=(VsI)ii_hgCJtLCv+O z$;LKEBiwBiM}^u=>3_|x`l=wqvw9R1dJK3lc0c8U>KHBFQj!8ncT^?rk>W{Jzl}e| z_@mbIYVE9+Tg4(k?=Qe#Jk&DgZDQ<^NoKDv3YrtYHy9WK9r^~R@>bCXsJ}R5#W|n*IXU)bcs%h^<_YAWVJ30X~ZX6NS4=Y6eEE1 zIK>AUC>You{F4lwOsLFfL*K|-T1JBMoq~K|1y58LjKtGXJT36BT1Ij5YEF5z?;+PJ zsnK;%I_r8l#Md{3cx^UUV!5SxgG8BB_~iHD|DKAhYZ5!%#e>r_t)VY-%H;l3=`#3- z5zx)rJi~#D!E@3mk7ezCJMS9~^nlOIYfY7|$ia&SXt&1p+dKx0sjjcHC8mgBRZiLP zU+|l@D1_bm7nG&@l*f7)dw#v`|9*BA zk3%}^F*u1aN$T)4+GBhcDao@(dQpnZ-{V@~i3IeR`iRlxx_+7y#3bp049k=f)pwb3 zwZspuCHQ$S);te7W}Q^d#5pv}=zploq$NUm!UPTzXf0 zXA<^{JsDg@utP+5hVK_ZdtM@u48IT0x$j*dghIE2_7weFOd232Jz!k(mR9*^OI0DW zMcvXIcUKnlL9v+C>^=${YHf|dz1Rm?FTO%7y&7HhM@afxRnA6##Va)`ogkbpw(C%4 zTHn{Q7FR2v_$%PcL5x|!JmOy@`a6(*fh0gj#Ji684fFXc#1iFVa~pht>8g0;g&|&f z9;so-fKsc%GRF`2Ph!+5uMI-qrF5u89xX~HNhI^Uml#{m>uoyax9@Py-jLp&>A@In z4>aq)o8Lwtat8*fx^Uw}wZni@oe^Z~2;o=cuZKWW_in{3& z6`f{tOS-5Bv}gD2E#F(Y%hOq&ER+7vv z-#M9CZ@{NtjF_!&wlE3i2KEh&;vF(dt3f4~^s)I8b5yauISTqgwyMO$g&80JJ4<~uekV^rN#J@x{wF)iTh$x|nA1SxTjYtjTfiP#D*Iw4SfB zt4p{WFZHT}M($yKNjvh~<_!;{?8o&9Ug+6H1gDu$_$Z!L*kSy^{Yx=%*g+$d~xNxq{Zb4z}>_$0GO(3hMbR; z4+h==m#k4P_5bJkZy)~Q`se-I`d2mARx%s#DAD4f>!`xhU|@PMD?d$4RdhmG(nl9Y z-uozEoQGDh3RvezvIQEVxgMHtQh3sys3|exnvh>>=Wt>q@rn%JjLd+{;E{@@;Hb$L zRfUlvyXQjphUSgSY46EZd(}Axs!(c%m&VDJ@vuE^Sk62vC_m1z-NiW15GV8l+z||X z9=uLHf)|zM_bacJ`yN-geL3vk=$}`pM(_H^Pk*%hQ9bQ0q@IDR{w3+Tr)ajNm)MH+ zMwF>vp5Urqe#*5&z0Z*1r0IMY;j?^>-uChx>W@f78t2ugrTb@hy0$Ifp)PRE zV%`yRM|vO$&7I}SbZlFGu4z5Xdvv{P$MSd=qmN4Kdp&mEq{L7gdW#SuqQ^P@By;Kd zHndg#cex2YdaiV?z%x7)yz=mc;H4v#dzQ~xc2J#Xv~_Xz_NGV|F*o9g>3rI+&-Qx~ z{Q-53^;VBVG17BQ!9ZD%^=)Xi^lp39gf;G!k5o1+KUvY4h6ald!JJ&rDpK7+P%!8!1-CS0eW7R623yn=yA&_ggC&5tV>o!M=_SgG-PuB=~Y z@~%)42p~4&Ht$aLKI_{anhC4;qtR`p@Jj&&aqLtV7z`rQ$l6TA6yHrV-4 z8spD~KbP^=a4AIF-vQVDLFG=>MTP_WRAOd#u^~<1a6ouFuld7DZE=S9tI+$wenCuV z3E%I9{FB!@E{(}iqr@G{k5x1@?b7~Eoo9_daR_kyj5g*3TNPj5A><`$wJg_~q~$`n z+rV)cTH}?GF_*j}E%A#l;@sw89K@s%8<&rBvHebR?g3wBFeerb1qy z<;2K5UkE&3M!?I3T7IX_Asf|utk??!wK4w{{@q|M|x5yv7Ge3_5{9Dxll) zI4k%vzQs{SEY7m>8e`3oo_39~rBfnnT|Gzm^2a}c7OQ0auEO$~heFSJt+z19mLf&B zhnEhiKQRzkqn-!$9?wI=oyMQGtaV`3EUOupv_cWcRat2kYNj2G7njgcrT@HtsxbQa z>wMhZMQsI&`=P0}T!*7;y@M*Hl$}`YhvV#AN6q_gi&6^AHS2M{h8Xq5yx+i4OSDvP zvpAw$N~=k}uGwQ-@6Qy*9^cO!oZ)^lp^N&i zpRO&~!Ej%1|3_b>hFUZwwKie|EI8s_ovkE-wVyl4+IOyrT=Q|Yy^A+HY8Ynk(9#pZ zzz1!?z_V?$YPgzDw5474xY=!bXN2<^U3@bkZFa>CUoS_^3ap^x@eq&M7HSt` zrwWL~bhNbR|%;nfT~ zC0i;TW{)d3Azx|D7B9&Bl^v^KWtgs;^0hCF--*$W^V;rdVO%7W`{C)tppw;Qnn!0% z1oofAC*(8T-Fs`J97k4Pm-ZQd(%v(I@yBg?tOdWetY;R_uV%ABYmm9WuM^e5Z|GK! zMd5H#j)b+}DC@xURqUI9HuTLl#YnVHZAk*W=bpi8(i#0e-Z&IkKZHGRH4wecHi9Px zSVov-R|~(jkN>UI@=z(#cD-C)GY^;^Av!#cnhxL$QsV~o{cF%tkp%5-Fwha~lhZ>d zZ{2V&R^l3+`yS?Bq5L$2^G}9wKEpJ6QBeL4yGDXhV7>xkf(N!O6ICLh-7!E;%<#`nv{>Tk*ZK3*M)6Yr(Khq7%vcBSGF!%r>+FPfqs|$ zsCs?|clEp(zMp_bw)O_V4Ahe@rCC#BEd43%zMof!gJk4-KdQTD!nFKD16O;+ns^7Z z$~w9}aL}m zyofGbU{}cEg>%YlmiBA_E>T;1>XKTVH4b=vIv>w@=1SeGcKxyPn)|hy}{)yE&&-B!d z&i`Z6e*5(Gub(WhS*YEA{4LCj%_#wC8s=qf=EbPliQ|(JciYJsYpX>%(xaQmslsiX z%0Gbn0;FdXCm$VHBw4Xs6RV?I2O1tcINB%Jp}`Q2y!*?#gWGU>~SbCZNO49vV=1&qESV==j^*OYbEoJ zbeG4w%r(5k`3+#eH--A+T_3Tzv$KK3=m%SSJrXf9DJ@oXS%ZP3;qtXYXn)FAhjs7d zUG_E@Sc(xu8Y7F@2tchIj$RT!f6h>#r(atV;zL5cvc1*=s+oR-wa?bnUc-w=we)x} zaJr4F(H704u?v|0aqJvoTv%gQ^xVS7+4{4w{WmPgWX)fFr*{noPQXrWXy$-l%`J`) zj5=7K@EbWbP!7t*&i5kSmE$In3u(JR6W`r90=@wlD|GLL@lx(=#!bb8lj4Uur37#f zCb0v4JHwVKrC+EYxXC2Q^^v7Ya>Uuymd7Fnv{&*(_$TaTyN2sNdUG%^a!BK^<~3KI zdras5fLQX`yNUUFzfr%iI{6l}GMigi6$}gvR<6-awJ5Xs%12Mbmy=lniD^_(A|zKD zx6l=3fd{h-8i3p8siSVQ^bVKXakZH(o5H^90&m&CSu87qfqx9xfa&${40;~A0i`e) z$i_OeHD+@=hm?T(QAjV3guMjo$$VwVl^u@>;tEBCrwjZx1_i&1uqV2W*-&<>w`VW? z1>*(it}%)$W+R?=s%xw)XCtl{1=gvwi=PjlI`Bib`IZeDuizgYf?eA{erIFNPBpo6 zr#iNMa!pyyS2eS{bdzUw@ur>Xm~Hm1k>;5Gr`4#YnEnmJE&k}3w39KHg~)|!y3&$M z^v_Hq`oH7)<+W?=bfW+8TKW{%Zlqaw&(i-Q?Nklz$%t3bc)1MTH%4*C5O2!C>pY%i zZHI2miJfY-HBH2HuK2IBd{z*Y9aY@rCqiB>^4^} z<8mzdix}U^m;Vf!!k>W?1=U|M_^)#n4BR*Piu~};{_rzJHm)^bHox_fjOTo;cW&w! zAGv8=Z|NK1KJL6)@&@Z=7m3oMeJl2|$_V-q178Nlu|Fx3sq1?4-k_*6{S97R+#|$W zR$p)T&fb-8kc@S`E8YmV9f!8>@P%8R5gPqS@QAhK-&;-__Q^}%rZ@3En_?iw)qjz> zn^JwTN-)Oci->GoOK%m@N1goQJUGs%5izlZ0$cEW<7&31M!sF<%vWXJ+$#&_%d*C- z$Sb~k%ee4vnd;VEnf%7*UtiX)>$SWwziTAFt~ce4bvNC4HTjM5waovS%e=F9%o`T) zYwRpIx}xLbT}G#QQ@rgRKZ&96o8Pd?vY|%qK?~d)Enl0~mZHs}*A+bXzrLW0M~hcq zr#u%oUON|WzkQwc*Zq39Kl%0R@Y~r(($@8!ecik%0W;J)d0^&Iklndez@q5o z#MfcG1nsA7KncR#A{b=eMVpJaIHRG}++4zU2_)IZbrD2xz%#-DY3I`=b;-xe(jH!kLWavD+Za8UPMWiQP+*WAPM4ouG_|GBil~lodc0pVG(<0ac2EWoi zaH7&V9vZtC{ab!*%)Mtcy-NJSE954ktX_ZciVfFa;Of4q$oFAS;Iu1Ek@6VleRMfnNiYaOP#e#ZTexiM4-Fe{vwq<*+u4uun1_@9RU!7Jfj# zYZuBeyj_Ru9nNGsQ3}=v1Czm1hrOy!>gWlB6zf`~H|8vq$)qpTcJ~+R$-ThU2QKMu zIZ@grj=NvgSDl9DJH@8zl1@;|7&zJ#t9omL8f(o2+$+2*GsZU=`18xb2J{0ig6iOf z@@zjVQ3eidGp;QCb#diPVk)=#zX`Nqm&m_6%b^B@P< z2?f_U*dc$RBPYV+9VNq^mGQ~8$iV|D!_kcXGTO^<^mY7g#Cu|J6NbAP4lh+)QKbse zf2&({;-~PQE=v5V6SLl)B#nVL??N@AitE>3&asmn35;jvQ*2{_scHRfUeW;XgTZ9e zq%L0jpmPE=10|5Zf8wMA(b);&!nLk!c9KecoT6}ZGDczrD*AuqtXJ0<g@Mc^c2MIS$jq$@F|HIiIdI2=ZDz3MjHN#ym71dte%0j z(}#K+(CSXui%54Au-}Y+Lnto~@&|2jwvdLIMQm(&PWFBRXmEPJJ5=JQdgcKaMK{ag1kNzfWe=>-m29>%3=%>t;$fCnn^-ZhyILs+iLMlsXIVR`tJ}1Yd#v zTc4@R|AVS`cYJMjF1iM<>v~VTp28wW6vi9ctrOkVhKyj%uj_$%b;ZgVLo!?U9f3O>Ea@^ zin6d_|7Xd^jOUsL193qD>p(CdLGyb)q|0P7U$~F7yUt5`56*B9^>5%`gt?ef;F}W+ z6swOJvsMlUx`$1oS$qt#@|?b)Wn2mLe=cC{ocGnv?0DDvD#|Xl*YVI*k zY*(}B$N?%O=lp1i;UU3atpPV-%ZG&VNY!7PX!Zv60oxK~ouEtKpcdI4sb0}T@n)Y| z(tg%Q%*m5&6Maob)YP&gs+A_^)~d$XS~WUWH^9MDe!F`6EL{exu^xAg>d3k0QRm@e zwvMl+~tWc?Zl8RC&VaP(M=*=jVT0F5R5`1+qClwkRPO>=7 z$~wEb7l*iat=+5yxp>EVGw+(@V_B1 znjo6a!lLO&J=p_Y#xW*`(|WpRlbt_B_Rt)%BA^lN;m3|v^ctIT%)QJxU!CkCQ;G7aoAlb? zOBACIa{^87Feh*TS2yVW>+bd*CPRG$+=G+PbaLPG2ISIh%Jc3~y;Y?j^zhcPUW=|& ziHUHwz3kWX4xFOY=u*WP-9R2twVe_Dd>`rOd!}|pjC6p{o2_cCpkficUDehUBT-OS(&}+-Zc1`cb=VI`nGlA~eeJfvTSt_LXGzZslptv_R%f_d(Z(cv|BxWMcV^OfA2Xxry(| z{KPid0&CRYWagV7hxV`?cr~dlcrm>1hS0w2*}hxndlDKX|OrdKAec@#3J~!$VAwOAx$aSDzoCg^e}<-QSiS*K2Y1| zw4Tp{{XF$8W-Usy4h34_>wwv0A6JFBKZQ5zG%^%82=D8)xW0kw2ZYra3cS*iCeBgy zGe1y;?4iKEJ{Aj6({~mUdUyn~?eCzLht|{1vl3!mTve?{;L*cqHVb+~w?1$I*26(z;D=;2jS zRp^uwT>Ub9FvQIsx2G0ftBF#it3=vkkMO~!fD)M=<`YtH@Attg?yagqUdr?!zS_mL z*kOl5%rU&#A|+m$=W%*iJ#b*$=(cfEk&C)GSNJ{a(!E!yOC>EM?j8Z% zLmv3rylwBo{z5Gl*UN=Nfjsp-#I-pJdXG5^E+0jd4Bb`8V#O}XkHnDFlZcIHi2wny ztJTwVg_QC~ z!3rBtA%lZ^AANTIBSeX23*(jA}CRV|Aka`|xS1x^{9YmQN^10kJoG#Km z+{-LlO%u}g??R-E4%R4YYKL9_xi)s%Mu=ZR&I5)XqE_D92)J)_F&n|yVO|n46|c(t zOPql8igJ$!bA>gd*S${X)VIZpju2dN*??uI3O;dbKG8pkWD<#9Y2I}3PdZ-AgDrzs zX%fwtd}>w~o%mbbADc40+zgA#E#fm0PCcM2=+cN|+D4^}5@F%5G>d$<5UtCIKlzn@ zg`(4eU$Nh2<1;Mz8{32#tOU*APKE1po^e%5>ucSdPCw&M7s%4HGN18}lZs3;K0fJ} z?Gsq^CN$A^l1%1x!;6WCx`?eN>HR)KVpSoRPjBT#Lvy`d=S9gciYeg8EyVk6j@5Y{5zXu&fqbwi_0L7}(_215&N6ufRj$y)u*NmuZeZHzngdp1{k@ zy&yjVyx3j=C~bys@GHFXNk2(@t&Q8o{Ab|@GQjkk%(^=ce&hWe=u>$XzJyhUpr!Ds z-g=;3Bonto^T*_1c#75@_D_t_d!5Pf@{s1DCY^o?ej!<3Zdd8v&B^R7SMT?d$&uze z#J9w^{CCDUPagJX#@y~5g{v`UruVSl5_5<5Rlk+*Xo|=zJ(+;LjBDctbhi{KZap`k zy;;|J*gqvE9VM+XUA`iP>bZt^mG0;2*(i?tUiBA1Pf~p{(r=6`>Lm*v?BCSSTG6*@ zCm;4d6w}vaQ#QG2c2Tdp=;J10-rQNFaQY%e(4Urz6utg`@o&%{m*2WV)*U`}*#GmG zDd=l;Oa}g!#iaVudfieAJlKnRjnaGaVSh%9!N=NP1U$rfEnR1S_9lES|Io(9J3;)3 zy-2Ck{}JV;#+(e5vndbNqVMWPt@p$#LI{?#(6-ifzT=&gIj^|z!t+^<`D z5^t+wxVAKmA)H65H^{I0AHvM*P964_V>e!3AE|u7&xbzZ)cRB6Ug!O)u%E4vzHN`l z#ydwG)pjfRk|6w&?ikdG&wqK?zcglD@8fSoiWp5%j48^mi-<|rzMQV;BGTGoOf46= zD5Bgl@VuG~xj%xV8Fp`i!o}Eq38C+#fF3|AY>bRoqGR&0S|nyvn_%HB2kp_P6BK>S z@4I=e-ggTmFeBu*U4`_{KHv0wGKrNGyw@RSS0QU(kDXgx3d=^!DrZ7liuh8uE;6!P zrx}ZrTG4Wg$aFAoZ^()dX2Y!+=PD6%UStI(`RbJ z0b0MCzVl6<-1 zs7|`OXu^9_Q7I za<+xp*&b;m`Xxvb5@`AO)-Uc-D-N<9}zR@O!&znMft51 zW17CJu=8uWhhe691)JKUU$vU%Z40o4oQVkxm}rPl&{+nz>a?u(Dkm?K>c9I`#fw9(oOpyRaZ|>|OisyLJ4u zHgHhl5$r@>8?lVepO6n|*1umseYfZT=4&>}L_jv?KDF0N@3@Tfy(C88Yb@t*jw)h) z<~w-BxT4I*P9!^xedjq!(ts}(J&G1H6+@Kvw9W3sb6NK+n$o{{APFa2@TRoP>7qQO zS2xD0kF?l9M>G5OcI)-ff~l;`r>fv4%J1EoSnIb6QZRq_<$dn_%LZ8YR`{T$7NYFY|69ljNbN=48?G*gdY0P=iP}4g&pFc-F^8@cObE+ zsW88>TNCvl#`R3+DPSM6j;&jQSlV^=(LD?+uK0}?xhtaE5}Fn?y*GB7%;uZ;AM;I9 zv{8rs3u4&pZUKc@!Jlr5$e3|5A~O#~SQ~&6iZ-IUHK2C~?N>Uk;}EvislbWh^Um6d13VrUy#<*af9Teew+jA@cpgnY z!*=OD+K`z)UR?FhLa_vWk_R<@PGgZqwJk7Jhv4ul)-#_7-1nI`5g1$Jr=j$ zKbX)q#ngrIu-+J+*j4x!8E~8%{i;!%*I#@2!Tws+BE>=9u&eOH>*Kz2SK-Wmrimj$ zk-el1F$tycOIxE8>%=i)a+?JnZaBda$>L{Y^AKfh7Bk_U@koC}#$oXYVvp;@h%?rl z{RLWZi~6>G1s9L9C@}SxEtnDY-jd^&f0T0x{0*}y7{1+Bq7z4oqZE>#+~)b#7DZE= z@$diE&_4!I!vb}T&sR7hBGGF6OTw@1i0GgA_BilG;=)I7d-Qf!SWga)De97Z=vqDQ zfAhhccF706ZGYm0Z}KY-eJeh}+T%XUR|Mg6`Gs$0J#pyUKZW}E@d_%d7@jbGtHaxmLNzoeAj=OP__i?WrS51AovFX|An;(fFUK>n>z}J=ZesqgfnUdn zIZnR&BfkC{@`UwUUDONTWPaDa(9!g*@C2RiM!wFk(SM=-4%++Q9hiI35G5#GeV8Ht zj7YY1Bta9>;6TLmFF%_nE)vPEVyx-=eZ+5#zF(Xpk{!FnNHZe5RQidayxF%w+$?@A zkG?i`jJwkKtrj!=Qze_J&=DTD81+#8^-*8+H3C;NPwQalcWE6V({0R!_W_38 z=3%W0MSUAkE6_nKIrxf|OF~=l0<{JyJlTWR1Yn77nXAb0gyldEYY*Shw-^@>-R@Ok zrCzMJ8=B+2h>ciTZ;!*3;yTec7`O}l2;u}pSq}$X!BCVnW+N!G2QSM})ihJ%bFzPY zi%9QX89X=toRmS>?Y{+5!bmH+He-v8LlTx$_=KYC6=HW7y4RZm~SoD8=`7uG4rUGjzUq#Rd*? zgqcofxbstaL`EO;3x*UC3F|VM@>d_C!C<#3_TsA+b4DvRO(Bbh-sEQ14y+9O&J|mk zeU;3|j?H&R#kRsPx0;`gzzDWu@Ap+wP=f!=<-BZFel34hy#xBLM0nG32M`TBz;XeP z9cQaa=F?vGzX=$b*E|ziqf0V--xz9-&H8cV&e1%KWPa-ex6qDO2x7LE5KL_=)x zSk^3F<4_X#T==GzKkD?*S32R5T|U5Ijyux{eaT-2-mstdv3MI6n^!B16i15;B9iqs zjAhny3)XYCvz9j_b8^a#c6P#p9inLqII?d|e zGLXjh&e@%}}ICk#Rna9&vwV znz%u+=@%{gbB{X#oFwCbeA7fr=fAfXiS{Co+wpycV4!kHm|*CL@CR=_kCuBwEmL2l z>5^<0!|g9biL0kQ1@!3eyCZ~UTlQaDOToJzXE9A=>mHu-i`ZwTImTMe+Ppy{My-h! zGd)oi4nR{>na1*o3zW$OI3-wr-EiQ?L*eHvL=yby+Wi>Z&mAJ>JV0ooHdY)Cl;Ft< z-R*Fo;98kvl(}<=nDU@c^7b)G$}4~EvtT}@y&WsLVyxdR_*lPF2mXRlQAVd`3^!KK zgzcB%o5m_eBRFOB;c#rWfcF{0<=5UPkn(HqHF%HMo@*ztu`&r*$KW3ax#Si1n^(53 zi#q-0l}+oWcKrUzrpGl?Gax%?mF1h#)3@(_^NM|4rq^~kBKNm;2d+9?6B*`#X8!y8 zZ+`ad)-ZHNo;eH5nFP$)kocF-cOYOdgqN`S*-n%I4!4q~xI~4)(GA+!x262r&hTf- zx9kIjJ1y_q;zAy90BU~uU+VqqbZAdEZdr_atbaPQRbISh?{~H15_?(w8`!C*L#s=D zXSZ6OqPNp2!pZV2MzL{YFfcC|{%+Fq;6Ch^4Ue+OHTdbZk}2knLw%z_RVJK%X~VNJ zgP6t*n`DyqjE}{<{1$ZiO+>tG@IB_qL?myebk@}^S;~GcPxmw;miR1Ui7ge~u9Y~S zqsfYE+{}%~wjPjor0SWL1nlswL*>;L52Mo$;na`qYpl-v4j$kG(H9!`7?!5BFi6paF!dPNSU7x_#{!;4i|^`Ks@U`A zIH9oqn;4EURWS;dDJ{ZRGk}H47=N~W2y?iBM|lV*f$CV+B(<=6=5Y}AL149h8TvBM zOTkaU;gX4hc$2tz%j-?o@twif3aaeDcc$fA^l`eiB3QJBs&-3zT4%q#tW^@~{Ibo$x z4*x9wUc#sC1m{axZZj{jIKL1NAi6vsy4hFFKESsCjQH+SE__?F@b!oe?2i$a6$9V_ z7{I#Tz6kcjC*6iKzyo-)A)d>=&IPPM@#Tz(q3EtDq3Es=owlpoob`Zz+f^RdSX?Qt zif`dk7L$N4FDo0|^VNkZv98^9+uaRo>L0y~uiXC3TaS3Hco)7Ul<}x{H~hCwNpoFE z6~|mw3nIXfyVM&i?RL$TPPvXsiDf6*Np=%cC>CUWI2L3*xVYqJPi;+YifGzm*Pl7H zH3>XiQqw1i?=`XSPyAgT_w1Ri5lsiN+9;E>DDm=tY2~>s_iqWe!k@W+OT(6krVe@c zmIrV>2t1V9)cIfPJ+Ni>wR+mqySFStdDc6f`L2Bbmgl~!&3f()o&3jTx3mrW7VlyB zeUL?So7}MV1OS~%VaS8$2D}CFSLEv85i?5uY+~F+ zv>N6)!aT-GiI{SqF-T3Ses4lP;LZ4IHy;T|%w@W)hNgPRM=w#jL)CGeua{x*)QXS`?p1$0Z;Nj53=v7Y?SmBH^v$sSbXFC%VVOwn_Kwx zs6~eZ$%sb}2C9N#?2*^X;t1(X7Wap*2Zu&jHLSpo|G~EZ9wT|bXB*ZnzJ*%cxWYH- zyEsxj8&t-JhrW@6QPsL9afr|TProRy`p7nD_oMhJXnWuf)Q)jBuRKV?A9 z5L{Lk-@S=%K+Pw^GRBjDPGUNwn%jTbv~NpH|CYhHrkw>zzB16cu%sbC(qPz)$zoy5 z6E}EW{`#VY;Ol#OE0b0s)_ZUg)O!s0a?{}6<-EiwM(4GwaRra^2HPSj zp^$Mm(c+VAwQn%qu;2B=x(%E{_rI5cvkqf5dA;Ya|V;g zxB{Mq!H?8)?&zD}wfFi=EB?K<<>4ET6YHu6{8as{B}~D;TyFZVPkAZ&+1R*|(HomM z6nHy0OCssAw{v+g@S|X89{~UNT0aNes-Mpm&d|36bu{-Y9{1%>|4&6Xv0pd5u4M;$V>0|YI(NE^8TO3z6HLCD((BsOwvr- z(1sSIH%i*HkY1pL7AY4cP1>PQSP)Pv=o%=vQ&9*P+2XpI(z9L!bIzPO=ghf0=ehi! zNfNb4EAEZyFs%vqo6nUJ=L>e~Id3a^C-rNh&$W`HndUY9tz5xdR+`(s^AHCDcDWc2 zU4j2ld0`I@9-}ox+vugb(LOs?+66@2J2pMHY3^k%*R#nD-PT=-utU1cjonc_yxMX( zazdN3VZm^pT@xGl?cfuhMUbKXwl8A3Hiz|o;v~6&@R4oW%DK%weC$|vbB_?4i+>Kg zg}0o!GEkquTQ%?|=PRNoDwdPAXYrk<;Lo8^Fsa$r932!FO;tJu-rA+vxoc_2M}+dvoRrN{HwPnt5SV} z<=p?@p12cFEJANdah&xUbMNphtTs*)vgcvv!}~_?<8ON@Yt~SDo2NoqlBYA~z=yyI zAc*dB?olF)`_^vpre#g`=q40UI^*urJdX{UL8p}^#(i53DL*&v-?T-s=eH>Kddsp{8XJpVteu0AH8?n|#{j#PyPa=-6U*M~N`K(Ju8ap_->0kC z_h0x%VDtN|wv;(f;_PK*Nxle;uX`H}X?3XU{JvY(*C|4yraLma@;8_V*2_|5rS*De z<)u2!wI%BtmdBO@#iKB`e7mAKPy!uuoAi+)T6kX-e38ibW~GW2*fU0{5S-~p29J0v zqCOE|C(h0SEVgHvElUqD}JB)j5`hECN!(yzjy zrLfE~D;XgN%(6H)Zyw{8PwGtCjA+MP$HJ7RQUBy+Ti(HhIlz&8YatQngzZoW?t zMYM5G$Z6uz`1JX{$e06;OKVwN!1U_cPRD$oLI3JHt+7sFoy#5RYnQDxt*cWaJ6C~w zKJwIjUxfbBI%Ybs;p<20lq6j1^qm{)lvJl_{j&83*I!(pwxM!^7q)LNJu+_N@{Qwu zx$Ku~@TBonY)PGx#=O5=Q&p#!ob!EA;xBwp=<1Zr{5oZU<2vh<3`d<} zwy(xh+4(VeDhFlBMT#tYoiZM&C*a7#k$^owO`#Xjeo?bYjySSM;Vi;1ggWu`D6hA(5jH-TMHgzq>WhbRU8C!upmm{3?p$}&qhU%T=;Rtaqx=ldC+E^2|s zS9H*SC`7vWkI|mZcYCwaR0~YbSga?;vs;-3Ghfm`ge1FOsdgHHUpOEsnat75-PTb3 zd#m<5$!B_R0CR^$b>4*-=IaIqC^xyq>OJ>>{f`c2R9cAdG~gfoCP{^!tmbahowXy^ zf2w?5#S-v;^X6ZeV{E0|c29nZ;dbUT25#vwKudz|FyFg3zEbH0!o=Ppjgm%7Ky>td z9IC-?5V-8Aw|9_E#U0XKh0j0H8r7rYJ~V8%Zikc-x@WOR>_p-A|;(sJ`HjK^kO+*o`UC@7F=_av>J4!L6;zl z1<;I4nIxUG3h&$^T?aA$XM^(^`ZYbHD{Ji6U_~a4+gfK>qi&}?YQ%f9M?R%B0tz|Fvj$%|`-PKcw|o0lDMLpGh$=LL>f8KL|D!@&-u&eq3X zf~*yJG84^mw@C4JzIsa|%Pw`3t_<)m1@6!%T|&VpU0UcZ!}oxB@_FvX3thtEBDB)2 zicswYTG%;AACHI1Xg$=8+)6gHBgO5fe)S|vmC)+XC$(Hxq2(c7S2AFyA?o)Q$l z`I39`_i0#0zWu`YDg5~Q1`XkGkJS9b%T)^!B)Rz$U3pmwG_1HuiPd>o(7M3Pqkspa zm6EFSvPJi}IV1AN&E|YRxSYV(IM?@_x0=O5*M z+*JrVdxflb9RP=dW~v9F{f)8}plk)iH7bM$10QyJPc{-t>`eDlGRuRlS=Kc77VE8U z`WD5&;7{l%kXikD8Q*OR^n>fCSAFCPY$Z!BA$ypoqpIFjh1`jP)JXdC>KDY`pGHTo zEbK~_<6Sah{{?F=&FiqE3#|f8FHRQD9JH1yB9PxTDe=-Z56d8VtEl+`JKNvL8YvpH z_U*1)t0v$`bu}XQVdot!+<3@s$49v{U9^&4_b!*?OIVK5QE9i!B;&lBeG8uidPz9U z?E=yl@FF!G+&)-j?IFsaJQL9PyYl_`1AYAc_%j^W$S>=}Piy6+uH>q6SBE^^6~-%D zgVZg+@ERlC(}D5i zTQLA6!U?xr;0}|dzHR_C7PR>G$h70*v@CC$o0+EDr*szMn|!VqPQ$^Sv&uNe^@;YyOKamPs_Ix}SRLLq${kxwkAs6O7oMTX>Pal$Lfi(b(18 zCUvVbDQUWlhC~@Q=#b*XbqGhey<`u116Pq9(D%zYzcn4b#tL6y?{;Zcp05e{kD?^h zQwW6{wp>W5?I3!v0tlcXe*2Nppu`#p@G@N9G)YoCZ7rP)^xZ&TE-+Cs7mD1Meg z*E?Iu_t`r&;P)}`Qho0tEv-5n^Lx+eFynm6SM5TM!-26D=}xZdfF9)taDJ($k$yk@ zWA4Nbb4%kc_&i`)ce>+z5wX~{M{tL@og-Qe`$6|?ig+%e^_;?Xpw#wHy7&iB>Iax_ z6X=2o9sG+y%q+tME~n5ly{i7$9V!ANyl|u@cVHHHm1d~vRVi{|bHpBYl6KGv=?{4ETQ+F|rTLx&my-hm{W0QLE|3 zKh3SA`|+Db(*EFlu{SUZrEF-@v**ZaPm`*L?uTX%tJm&F`^JGA11UOxo<9T(d3-hU zHxhGvRFn1yq|V9ItJ;Rf(hdJ3-(%;K7J|Vd!0sU2gB&+BsZr=bA%7bB(o3xm%Jt|k z_2@6Z2E9c{@)~J@%K~moAanr#eqf`8`$sJN9FPu1jfE-J+awJjP6Dur}#Z1zF zr!j)>Jj_sg}(te=QH(qnb>dp$0pmlOs8*JQu12l&A5CZN`_)Pdzv7~hzO}D?VSc-`g%W;%pZm5ns}17hV65Kd{Hih}9cPO7On~S`*C5+m_gqB+BEXqzXJ^=s4HK8*1#4 zt~U8Ju%;-zSdsuK2hY^X5opW0D$TKUxj{Z+%|3TguD3VH z(XNZ&)S2XpnVWv!hF%Z~Zb6Urk5H!Q{5&BD>YcEY)@i{K`3GF>IZKdKC?QBMWLaU2cHS7qb1C zDrtL0@ie-2mh$Zu^uKQvdRr5unlGw*EUHVal-5k8R$yB^p*0Q~e198E=;V7w2`GE? zl2X>&;(Vz`)S%3RcPrvU$4d2WnzKt_e?&RHtK6n?XSc&52zfjUJ)9IxcLbCsSn+x6 zb(STuoHChgU0LK}C1MA-Zru^W>#ZU@r3fWUOCLM;8m^gnk-H3KB#nwYJbSE8@YqHt z36iIaf9D-VJVjI_?>-}ctmutvB8Z#~4~C!FC2` zR8#AqrbmoM+wxPT3aQ_JpE6bkR)sr9x?hUwj?|vVJiOCB+;txLp0THv>@6K@&uKs0 zEeJ0qHrxSwHt?w_N5N*1R-w-%4L;?iGS<0S&Sv-C($CHw>y8u*?s?K-XxsKCRKg~i z+0yNmR2JA?Fk3v8CI6(iT>8KZpAEQEU|VHh;k{p4?xhm`Yaqo_xHWt3Vl0nZN>rXYZ?5GP#j|-3QgZ59K$P4TmV z-ZYmVD~wB*qvd2+Dwf-QEphTuS3S@RM?U^~snUL@465N2aIQ0NYvzoL?9Xj9*uj9tQ%Hn|ey#(>jji9~B)CZ=>8aQtqj zDQb!>C!aPBS3g$T1FqM$hrJc)+(+bESYis0MC+NZ(=6Fmne4TzDuJwt_Q0G^lu}Tw zPf^n?@PC9^@+Y(v+FbCn1Da0QB0%dq`KaL3USLM!ikmV=W-_kOVmEE73;6#daJ=8h zNY~0@y+ZT}>sIq8iol4T_fbd~9dL*D2k(Q@h=Bg+4ZkJ4KhMWn2X6$!@hubOw*Lj) zFkF_%3&IwnGzBL!ibGxk48(O{iuzWv=c9Hadhws%Q#AU2;{!1B1kwrp2@Nh`%dG36 zb;*$ZYKOGA*7&x8#>89I76_Lj>ND~SH{F%=&}OoWO;3=LRs{TS5BVNoM$#M{$u6NR zPY;!a>P()Au*&!UuqO(yt^NL26_n;DK#1f9XcZbe@5}=QHqJ1$=WOSKseni``Ja z|4~phB}k=bi(Ivj3qZIb?@>gd^Z2KD2edAKx_9>be~p>xyQ2qOn;+N1Vt?zotPbRM#KcQ`4 zL;V84?-(7`;Di!=HAdmFtcIM-a%(PQpn!tTJT%Oq6U>)(rENmGxbW%Tw>)a_nXKm=_1X^oe>eg^O?caH{@Q}xR=E2wP zVf_V_2B;y-dH;E8;xm5a#R=GA_KlL;r|@Uz(*# zQFer|Gon)EUQx%K9^3&h@B|F#tD6zm>$RnFIa9Dl(6@pS=k~9{9wR*dMrz*i0+%g=+JT+fH{H=x0zE|@nkr)XSEIzTOF_O= zH^-O&szxa7<~Ys=34p3i2&^rnpNX+Z;}Iiu-HxGg8*S&yZ8l~k3x0~z!$RrNbq?s2 zrDC09Ch~2~`5Mt)MmxoTe`Vr)hZLb4Sjs`cv>Ye`^iAm5{H9^DMtj|76F;1#rIu-WGDP&w z&Ql4WE7hlx=M;BC3S{~=7=yMQtC+CU95sjNr7N^kPV4uVg)Dee`QUElUIR0Y$!b^; zhyB3~f3mX0g?n~3{sZ@7v>u9c?cmZc>L)Bn;;CteC@VutC1#Bt zPr$ne>2@H!h_%xjIsoofg|(tsgl0)3P#0pP^lCnvN}CrXZAh($Jb%*63VHZR2l&$T zE=c(1nn1Coy2-D+cKSYRVtZ^kboY8#rErZwcYQcy3#gn6H^`=DtZ=@8 z{z;|=yP<{Z^EArDm$%u^!(+$|Sku!z?5ltpVW@qkk!8N|GoAFgA~rxe;g=y2FWz6CO0!9`E=0k&_d_G7khBd z_lJJ%{Lz9oyi-w(map#fb%^Az6R%e5%Zb!A=@IoMN^M9wQ&2BtCO37v$ij}I^I#-8z=B-xJ(n@(4*Bio-QdBCMp$RWEEV6v?4)zo`X08`_7w@WeS)plXB4<1 zcp9BJ7dEjj)Wz#T%cMcaa5^{fR~AiH$5BGKsl7aET%SiXncDa@>&I>Qa))%!hy0m? zR2R7E`I^>Z7|iT=*GuDw#zXZhOne&WJ8;n4usa?H?$h|C@u7PSD^2uhX@!x8M$bj? zeNXkCc0%qL&F?=6dw8;#^m%mqc{TnU#KVV-li#0!H@zRaN7C&en()hkSnq$&sYT7H z;eXBPT{WkAzf=3r=Jq4 zD4p5&?4Qx69FWFa{x z5;HAB4Rp}wVZNx)Z>*QxXJNY=SMWp5;|DQ=FRZ=T{V6W8 zT-OBdv^lyXTtDUu1~{`utzCG}g!I51qqL-{ASIw5JQ6woI1raehapWWLhJmFo^f-x zvGLbDT%nKVp+^GhGei}v3S!R-oeZ%_oD*vl%f;DA(6C!#SNs$DfjOTZYfQ3}2PD7W z{Z?q9j*aMKoi*E0W`y*7u-_t!ErhrvG?&>$P=*3D0EbI)a-53X#Cd{#-y4MOlz=$1 zD-HX9vZsv3741_%n@AH~+*CfR5Zd*358)QY92c5|At?ehI22yRDk7PI{`eEH0AB0j zB<>LNS(V5m;$EEX3i>bK(5b0Z6gR|`DL${G>FLH1paUZ$%^?A3K({ODpiwo4g8p+i zB7p2>fb0u?+JN70ryTcTHl+RJJ{rkE|JyeT?RxA4sFefWTA8l`KF-;9WY1!jRx7^) zilo-=Sxo*if$L+}mh;POkT#v_;wMHsh@bM8r^EO^wQ5R220|;9Q<_@Tp0#!j#lwy| z4LrINQy>N9cCcMLj#1sP!`;vJjjkR)o^$7nhfRI~SDz+vd!YNEj2|ECY3yP1Bin=i z)BWitvPx!_$C^iWvdnM20q{$}voLGV2mQ@z>>9+*a7}h$Kc{fHN31{!m~OJuP62d_ z?a4;iyVIM^3*7YPSMlaC)#LN<-n<0$y_~uelAyg2hdiI{XBmW9wffi;7e|OVxo@aB zlErv|J-w5S`x;hsp(2)XB6v;F2F3n0mm?#&{lbwfDWMvgV@idqq*Q1V_8UBVOJk7Z z12pmrsUG9=&Usc?*@Uwmk}?vdtqE!ix&2i83tsqbhel)2qnG}LZ;PFlyrbDvoe#i_ z%IXJF1fbAVy0vYc?+?Aeho{vsL%4usTcAl)>xA}4ge#FGx9Ft7-nR}e@54lIak~5X6=Q$kRl2x z?iRlDT5x?Uu6bNf5g<7+B}kW0PK~6MCxGV2N11^1X;wUAQ6g|ccLe>@f?WQf|0w+6 z7~oYl=!ZudiRLzL4rnaMtr{_R;Tshb(gD&mpK*=1%7Ztdct~3-N`kG)aOT@~g35Xe z#>-S_Zlo*xc-Yop*8$Ik3N&o7R@JChTF@dqAvOj5z-q$SH=4EX$RdsT=^-l^;wnZV z?Y6bp<(^>amfn%b``#0Zsv|H=8YQy{#qNSCTk|Wu(GxXUw?l7`^XYFhn)4VeVREjz zr$P6C?C7qzl@=cFzuz@oE=P&F6d)k;k+?&)NzC`f36iWEaj(zIspV`#3XT`kz8kuB zBbMW@d#?`3M@2XJZw)`a`~+zRkX$5zo$>y7#tHck!v+aFscxEaVvhf^N%tr2Fg)q3 zV!s>kKMN^kLa^ z5Ci`EK_UF00r6k|Ljxk<|Jx8Zfi#f9xMj^QL$e6YHL;V)MX;Gp;D|!o4!`hb)yv7Z zpy02b@Aqm{{?8Li7ivvj7+LF9tUt9_V<);}vnHuuLW~|gv2en~iH0!~3lU}wm$5#c z5a8d!iT>=E1x^%p3S&IHoanOlIhXVHtKM{k=v(p?Z=5VZlH=x0J~uS~1k80`;+~~9 zc4Ejs4>PIt;+Vm*d#c1J?B#2%9 zvecXe==nfD$}A;0iU{c}=eqY-&Fh+3)?4V$m{p4-I>lCIPC?mOG0hXq*WUc69#Q{r zm*)SltjG?QlLTq%!^#Ck(~0t!2vN^sC3GB?lZ+Vqk7C027g{U3ZGvM~I0PN|KT`Y< zSNx;6o6jw3o`dp*ONA0m443M+Ka>jmh98&a#qXk56@NPlI3UqW#{re&%_|?QI&noR zfB8!3uWnrV&tKhg#gH`W%8n>?%>o_=Q-8kOhQeZ!8H&HxNKXUh&*H0fZnKV(X0;y; zZ0@zX-sv&2i~#fPv^;OIT;}wh1fCicgSWhGyUf`lf-yaNtyr%T zB6>pkPG4fpUaO_|mKy%{=_N~(UOsv(sQAR7p`hfl0G?LN;H#yP?K2V?WCTv1w&vAR zOD|u;7tJWKT#m53+#RD~V@JFGZc%lkY!hjAdx~!k{TG#qWiRl2l#EjR4DVOCvB!dg zH`4Sm!IT2{Lns!5`m5Wmy7o;8dX$4dOZ&PmXPxw6Qo~VKaL^YMGz>?1OT-{k4wUMK z%D|sJ04ZWS_6;w0iyF&iy`|N=9kpTOna>3;70}Iq1x2_V#{#w2*@QWs?N3?-mVBF_M;WNyl$hWxR1UP8h<4Ki z_`adGo8k05KHs4Cwt_AmZx$%Oif47SQ*Mu}!BE^p6SDp#+Ikg5t=a7}!?I2O@eIQi|=% z5?~FUUv_p|snmYB2h(xMOWjdi>-ViU>oPYBrBF_w^}O^2Cr&tfqBIw!7>BPHX#u8? z?m&>=I=}P-AYmk(8|A*wb*wvv|3x>a(*^W5dM$H-2IaS)oyM`T;WnKhnWbppO?G{q zAPszNEB)&1iEcio3S4cj=yR_qo%PzKXS_91v-bh%5pO=QiC*vF^;1jYz0_wiFwarn z)?sBbG+B+}+<<@l4UFwdo6%$sK;N^(81QGn3xzPp1jKB0{{g>kZ8%^nioL*5(89FG z>X0jJ%=cnH>2A@S!hB88C80eq(ZZkLeiO8mnQtHd!|_|2L*MGj&kfcg@^iBgK4~H$ z3mJ}cadx`z(8BaSc%*|LE4qVu6z5b{hIboqFc#u+)pDS`cJTKD^L?C3kuz|#=&dJ$ z;TYqOVv^o~*2Wu<>#2E(-?7eESgFqM1BVH1U`vh3!Jb3XwK3n!fDu|CVSSpP5r?b? zZ@Gqaz9T1Vbz094*B4bhMtc6HypS2#y{7VvIX+cdI%>NB-LmVTE!^3md6Y?G`;x3!l;n2M0DQ{2Vswb;5Ob9rjCv>`RBq~1E}Ec8~_ zRHQuKoSU)Pn&RNv_oUqCuq62))%(?GtfejLO=?Nk37l!TfEpr z@zHLvB@*%1f=qsxU%d1U%Uk$ zW4MNY_B7J{x(>Wp9@wNw&}63j36$4R+B?2a3+pjFJA3F_V-8aR@oiM|vjf8TNbv3$ z)3;^-lY^x#QZn-sZQAlgv;}xb#v*kW81%k}@>6}WrqB?r@8|Ka{ZyE<1U}uiOtQ&K&<-Z< z7o}qPK6u}aYU8i5xXspxcI}*<(5`wK+!mtLY4owy<7ki5IE=@KNfvoHbaTxmpjMY& z_n&V8_cUFPGWDo-6k3T&AkJL{d$D-f4v649p%?hf0d7X0hcq3FS`wri=�?bdbHO zHgwRo8}!eEKB7j|%6l28@jJkeBnf|%Cw+n> z;=RM5S)eqovuvKV=Mm^e(t{1>hX85^qe&KsY)G`tr zX&{1xEH3Re20MU|KOqB0G`R8iC@Bav2on&B2uC2)BQzj1Ak-rq zflx%4fKY=lCI4nVl>c7`H>1vbVJ8y_G$QJgr`E)~p<4@`0{T|Z4N_?qN+Z-S5XP=} zPA${?(Br@fG>Y}aSx{?1`8__EE#HOm?XzZk9>iG+&N4kmaF&2GqvtZtM&K;jlU;Qe z%DK;ai|0X{>2WsPa|CB1&h(zkIMd)vhmsj@4VR1a7$>jB*VE`8R==UeYfcZP1^fx{ z`ly{tZ}*2ZJ!Tg2UxgJ#C8&nu*sGI#i35`I9g0|Pk-5T`Svpb{-KevIUN;(AM$a+& z#t4R{#qtZlcKG{)4b}_~XEH-eTQHrvx>*z7JmciZa`*BB@V8)7jD|6uzUCxZm!0g{ z_aOLHZlTAlp?7~0BJEAIMIr2a(SNaWn>xU8_{^(?MCL8@Ewb-;HPquxv9pXTUMkyX zIEtD^VBQ_WYvp_7oz^6G`-9scqu|ob8F)L3O49`SLN3VjFIf2=o`)69f(W+`JV$zG zeaPtg&PF=iEd6W9PD1{T7`B*?kgu+(+7&tHriKUjphG$ykO1#UgpCT#6+hPV=pDr} zmaThun2aohAai@b-ty`OivXXe+Vh72D<+ z5m&YBA>)d5RU22X`yuI2X40~%hgPmIZdhZiM6MfF8aK!*|Hq>%H&#`yoMy~i@x$Yb z9;vKcxqkfvk396yCgZxH*HT75@%Yf2^H!|fn73iWrbX2(gsQ3SkMJjd%gm5N;6#ve?OaviTO-?7x!Cm?978~ z6XD*86c1WigG0oj$6>&6^Oy3&`6S$Od8@IdBRrbl?{gYj$_!p>hz zW-$m^L* z2X`mkN8vXc%f?Y?y#GLNF+#TTlNL3s`{z??=#E>YhA593vIoDhP&&5dSU9vi5f0hx zp>Tv{-(LDP&-~ShKhOH&(Yl%AZ7JOsZ%vvx?dklBzui=N`zkmMezlm=w&9tp~eT6yVG&Mhd85T8Q_k_bO@2X+lKc6oS*R$9* zYPGhh=|sJBt$${hFu!Qtq|y2PWxw3KWJc@yCoaq%`N+eInfR|I(A`?Z#82)T>TBpp z#dn6!Z}xW#!ps$D!apsCPsC+RJiLO54G7o%oQcbD90nG`NgORWo_PSWd4yE9lfV$5 zkbYBd?QjY)WCl`1KD}JO!`aJ&8nH$GWi)?g%7kYwIWBz~s za=8lq%{c_4EQ)1(`I1`ppPpBQq55JRO{VN)#_7oSdE{e}EDA>j=<^Ne6!iWuu52i@ s{YS;<94gphq??KR3oxGlI&@A^YP69p#Oe3#s@_YZdj?Ux>16Ex0*ChS5dZ)H literal 0 HcmV?d00001 diff --git a/boards/matek/h743/firmware.prototype b/boards/matek/h743/firmware.prototype new file mode 100644 index 0000000000..a9177f689b --- /dev/null +++ b/boards/matek/h743/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1013, + "magic": "PX4FWv1", + "description": "Firmware for the MatekH743 boards", + "image": "", + "build_time": 0, + "summary": "MatekH743", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/matek/h743/init/rc.board_extras b/boards/matek/h743/init/rc.board_extras new file mode 100644 index 0000000000..a39b81bdc2 --- /dev/null +++ b/boards/matek/h743/init/rc.board_extras @@ -0,0 +1,16 @@ +#!/bin/sh +# +# board specific extras init +#------------------------------------------------------------------------------ + +# if ! param compare OSD_ATXXXX_CFG 0 +# then +# atxxxx start -s +# fi + +atxxxx start -s + + +# DShot telemetry is always on UART7 +# dshot telemetry /dev/ttyS5 + diff --git a/boards/matek/h743/init/rc.board_sensors b/boards/matek/h743/init/rc.board_sensors new file mode 100644 index 0000000000..c37c3b3b58 --- /dev/null +++ b/boards/matek/h743/init/rc.board_sensors @@ -0,0 +1,22 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ + +board_adc start + +# Internal SPI bus ICM-42605 +if ! icm42605 -R 14 -s start +then + # internal SPI bus ICM-20602 + icm20602 -R 12 -s start +fi + +# Internal SPI bus MPU-6000 +mpu6000 -R 12 -s start + +# Internal baro +dps310 -I start -a 118 + +# External mag +qmc5883l -X start -a 13 diff --git a/boards/matek/h743/nuttx-config/Kconfig b/boards/matek/h743/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/matek/h743/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/matek/h743/nuttx-config/bootloader/defconfig b/boards/matek/h743/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..ae0dd4e10d --- /dev/null +++ b/boards/matek/h743/nuttx-config/bootloader/defconfig @@ -0,0 +1,93 @@ +# +# 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/matek/h743-slim/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_PRODUCTID=0x004b +CONFIG_CDCACM_PRODUCTSTR="Matek H743-slim" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3162 +CONFIG_CDCACM_VENDORSTR="Matek" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_PTHREAD=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_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_LIB_BOARDCTL=y +CONFIG_FS_PROCFS_MAX_TASKS=8 +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_SDCLONE_DISABLE=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_USART1=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="bootloader_main" diff --git a/boards/matek/h743/nuttx-config/include/board.h b/boards/matek/h743/nuttx-config/include/board.h new file mode 100644 index 0000000000..f322c3cbe9 --- /dev/null +++ b/boards/matek/h743/nuttx-config/include/board.h @@ -0,0 +1,493 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6u/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * 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. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H + +/************************************************************************************ + * 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 MatekH743-Slim board provides the following clock sources: + * + * X1: 8 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 64 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_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 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 480kHz, 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 board has two, LED_GREEN a Green LED and LED_BLUE a Blue 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_BLUE BOARD_LED1 +#define BOARD_LED_GREEN 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_3 /* PB8 */ +#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_1 /* PE9 */ +#define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ + +/* SPI + * + * SPI1 is MPU6000 + * SPI2 is MAX7456 + * SPI3 is extern with PD4 and PE2 as CS + * SPI4 is ICM20602 + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_4) /* PB13 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */ +#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#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) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) + +/* SDMMC1 + * + * SDMMC1_D0 PC8 + * SDMMC1_D1 PC9 + * SDMMC1_D2 PC10 + * SDMMC1_D3 PC11 + * SDMMC1_CK PC12 + * SDMMC1_CMD PD2 + */ + +// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */ +// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */ +// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */ +// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */ +// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */ +// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */ diff --git a/boards/matek/h743/nuttx-config/include/board_dma_map.h b/boards/matek/h743/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..693132c389 --- /dev/null +++ b/boards/matek/h743/nuttx-config/include/board_dma_map.h @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * Copyright (c) 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. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + + +// DMAMUX2 +#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */ +#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */ diff --git a/boards/matek/h743/nuttx-config/nsh/defconfig b/boards/matek/h743/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..2fbda96a24 --- /dev/null +++ b/boards/matek/h743/nuttx-config/nsh/defconfig @@ -0,0 +1,226 @@ +# +# 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_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_TIME is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/h743/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_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_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="MatekH743" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="PX4" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=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_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +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_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_NNESTPRIO=8 +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_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_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=2048 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=2048 +CONFIG_STM32H7_SPI_DMA=y +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM15=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM2=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=600 +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_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y diff --git a/boards/matek/h743/nuttx-config/scripts/bootloader_script.ld b/boards/matek/h743/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..511ef26242 --- /dev/null +++ b/boards/matek/h743/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * 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 Durandal-v1 uses an STM32H743II 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 STM32H743II, 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 Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI 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 (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + 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/matek/h743/nuttx-config/scripts/script.ld b/boards/matek/h743/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..580f63f0a6 --- /dev/null +++ b/boards/matek/h743/nuttx-config/scripts/script.ld @@ -0,0 +1,222 @@ +/**************************************************************************** + * 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 Durandal-v1 uses an STM32H743II 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 STM32H743II, 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 Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI 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 (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + 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 + + /* 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/matek/h743/src/CMakeLists.txt b/boards/matek/h743/src/CMakeLists.txt new file mode 100644 index 0000000000..f677ccf9e0 --- /dev/null +++ b/boards/matek/h743/src/CMakeLists.txt @@ -0,0 +1,67 @@ +############################################################################ +# +# Copyright (c) 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. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + 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 + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/matek/h743/src/board_config.h b/boards/matek/h743/src/board_config.h new file mode 100644 index 0000000000..01d899a7f7 --- /dev/null +++ b/boards/matek/h743/src/board_config.h @@ -0,0 +1,237 @@ +/**************************************************************************** + * + * Copyright (c) 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 board_config.h + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +// #define FLASH_BASED_PARAMS + + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +#define GPIO_nLED_BLUE /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +#define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_ARMED_STATE_LED 1 // Green LED +#define BOARD_OVERLOAD_LED 0 // Blue LED + + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ +#define ADC1_CH(n) (n) + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +#define PX4_ADC_GPIO \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* PC1 */ GPIO_ADC123_INP11, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PA7 */ GPIO_ADC12_INP7, \ + /* PC4 */ GPIO_ADC12_INP4, \ + /* PC5 */ GPIO_ADC12_INP8 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11) +#define ADC_BATTERY2_VOLTAGE_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_BATTERY2_CURRENT_CHANNEL /* PA7 */ ADC1_CH(7) +#define ADC_AIRSPEED_IN_CHANNEL /* PC4 */ ADC1_CH(4) +#define ADC_RSSI_IN_CHANNEL /* PC5 */ ADC1_CH(8) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY2_CURRENT_CHANNEL) | \ + (1 << ADC_AIRSPEED_IN_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL)) + + +/* Define Battery 1 Voltage Divider and A per V + */ + +#define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +#define BOARD_BATTERY1_A_PER_V (40.0f) +#define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + + +/* CAN Silence + * + * Silent mode control \ ESC Mux select + */ + +#define GPIO_CAN1_SILENT_S0 /* PD3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN3) + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 10 +#define DIRECT_INPUT_TIMER_CHANNELS 10 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + + +/* Spare GPIO */ + +// #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) +// #define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) +// #define GPIO_PG15 /* PG15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN15) + + +/* Tone alarm output */ + +#define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) + +// #define TONE_ALARM_TIMER 2 /* Timer 2 */ +// #define TONE_ALARM_CHANNEL 1 /* PA15 GPIO_TIM2_CH1OUT_2 */ +// #define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +// #define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2 + + +/* USB OTG FS + * + * PE2 OTG_FS_VBUS VBUS sensing + */ + +#define GPIO_OTGFS_VBUS /* PE2 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN2) + + +/* High-resolution timer */ +#define HRT_TIMER 2 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */ + + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS4" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5) + + +/* SD Card */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_nLED_BLUE, \ + GPIO_nLED_GREEN, \ + GPIO_TONE_ALARM_IDLE, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 4 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/matek/h743/src/bootloader_main.c b/boards/matek/h743/src/bootloader_main.c new file mode 100644 index 0000000000..5670308a29 --- /dev/null +++ b/boards/matek/h743/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 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/matek/h743/src/hw_config.h b/boards/matek/h743/src/hw_config.h new file mode 100644 index 0000000000..f289dc960d --- /dev/null +++ b/boards/matek/h743/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 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. + * + ****************************************************************************/ + +#pragma once + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 139 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 8 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#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 diff --git a/boards/matek/h743/src/i2c.cpp b/boards/matek/h743/src/i2c.cpp new file mode 100644 index 0000000000..1444ea1172 --- /dev/null +++ b/boards/matek/h743/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 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 + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusInternal(2), +}; diff --git a/boards/matek/h743/src/init.c b/boards/matek/h743/src/init.c new file mode 100644 index 0000000000..a2a531882c --- /dev/null +++ b/boards/matek/h743/src/init.c @@ -0,0 +1,181 @@ +/**************************************************************************** + * + * Copyright (c) 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 init.c + * + * FMU-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. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +__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) +{ + UNUSED(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))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * 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) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* 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; + * + * 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) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + } + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/matek/h743/src/led.c b/boards/matek/h743/src/led.c new file mode 100644 index 0000000000..2d60d89be9 --- /dev/null +++ b/boards/matek/h743/src/led.c @@ -0,0 +1,112 @@ +/**************************************************************************** + * + * Copyright (c) 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 led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE (defaulted to an output) + GPIO_nLED_GREEN +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/matek/h743/src/sdio.c b/boards/matek/h743/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/matek/h743/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/matek/h743/src/spi.cpp b/boards/matek/h743/src/spi.cpp new file mode 100644 index 0000000000..db673bedf0 --- /dev/null +++ b/boards/matek/h743/src/spi.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (C) 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_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortC, GPIO::Pin15}, SPI::DRDY{GPIO::PortB, GPIO::Pin2}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}), + }), + initSPIBusExternal(SPI::Bus::SPI3, { + initSPIConfigExternal(SPI::CS{GPIO::PortD, GPIO::Pin4}), + initSPIConfigExternal(SPI::CS{GPIO::PortE, GPIO::Pin2}), + }), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42605, SPI::CS{GPIO::PortC, GPIO::Pin13}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortE, GPIO::Pin11}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/matek/h743/src/timer_config.cpp b/boards/matek/h743/src/timer_config.cpp new file mode 100644 index 0000000000..6d68b94f69 --- /dev/null +++ b/boards/matek/h743/src/timer_config.cpp @@ -0,0 +1,82 @@ +/**************************************************************************** + * + * Copyright (C) 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 + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}), + initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}), + // initIOTimer(Timer::Timer15), +}; + +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::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), + // initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}), + // initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); + + + +constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = { + initIOTimer(Timer::Timer1), +}; + +// #define CCER_C1_NUM_BITS 4 +// #define POLARITY(c) (GTIM_CCER_CC1P << (((c)-1) * CCER_C1_NUM_BITS)) +// #define DRIVE_TYPE(p) ((p)|GPIO_OPENDRAIN|GPIO_PULLUP) + +// static inline constexpr timer_io_channels_t initIOTimerChannelLED(const io_timers_t io_timers_conf[MAX_LED_TIMERS], +// Timer::TimerChannel timer, GPIO::GPIOPin pin, int ui_polarity) +// { +// timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, timer, pin); +// ret.gpio_out = DRIVE_TYPE(ret.gpio_out); +// ret.masks = POLARITY(ui_polarity); +// return ret; +// } + +// constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { +// initIOTimerChannelLED(led_pwm_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}, 1), +// }; diff --git a/boards/matek/h743/src/usb.c b/boards/matek/h743/src/usb.c new file mode 100644 index 0000000000..4fdfafd250 --- /dev/null +++ b/boards/matek/h743/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 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 usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the 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_STM32F7_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); +}