From 528ad1e87d4aba286be9a5133ba775e922d2005b Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Sun, 3 Mar 2024 19:13:28 -0400 Subject: [PATCH] boards: ARK Pi6X Initial Commit --- .ci/Jenkinsfile-compile | 2 + .github/workflows/compile_nuttx.yml | 1 + .vscode/cmake-variants.yaml | 10 + boards/ark/pi6x/bootloader.px4board | 3 + boards/ark/pi6x/default.px4board | 70 +++ .../ark/pi6x/extras/ark_pi6x_bootloader.bin | Bin 0 -> 46152 bytes boards/ark/pi6x/firmware.prototype | 13 + boards/ark/pi6x/init/rc.board_defaults | 33 ++ boards/ark/pi6x/init/rc.board_sensors | 34 ++ boards/ark/pi6x/nuttx-config/Kconfig | 17 + .../pi6x/nuttx-config/bootloader/defconfig | 95 ++++ boards/ark/pi6x/nuttx-config/include/board.h | 512 ++++++++++++++++++ .../pi6x/nuttx-config/include/board_dma_map.h | 81 +++ boards/ark/pi6x/nuttx-config/nsh/defconfig | 274 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 ++++++++ .../ark/pi6x/nuttx-config/scripts/script.ld | 229 ++++++++ boards/ark/pi6x/src/CMakeLists.txt | 77 +++ boards/ark/pi6x/src/board_config.h | 402 ++++++++++++++ boards/ark/pi6x/src/bootloader_main.c | 85 +++ boards/ark/pi6x/src/can.c | 142 +++++ boards/ark/pi6x/src/hw_config.h | 129 +++++ boards/ark/pi6x/src/i2c.cpp | 40 ++ boards/ark/pi6x/src/init.c | 293 ++++++++++ boards/ark/pi6x/src/led.c | 234 ++++++++ boards/ark/pi6x/src/mtd.cpp | 55 ++ boards/ark/pi6x/src/sdio.c | 177 ++++++ boards/ark/pi6x/src/spi.cpp | 83 +++ boards/ark/pi6x/src/spix_sync.c | 309 +++++++++++ boards/ark/pi6x/src/spix_sync.h | 42 ++ boards/ark/pi6x/src/timer_config.cpp | 88 +++ boards/ark/pi6x/src/usb.c | 105 ++++ .../px4_work_queue/WorkQueueManager.hpp | 2 +- .../src/bootloader/stm/stm32_common/main.c | 8 + .../broadcom/afbrs50/API/Src/s2pi.c | 6 +- 34 files changed, 3862 insertions(+), 4 deletions(-) create mode 100644 boards/ark/pi6x/bootloader.px4board create mode 100644 boards/ark/pi6x/default.px4board create mode 100755 boards/ark/pi6x/extras/ark_pi6x_bootloader.bin create mode 100644 boards/ark/pi6x/firmware.prototype create mode 100644 boards/ark/pi6x/init/rc.board_defaults create mode 100644 boards/ark/pi6x/init/rc.board_sensors create mode 100644 boards/ark/pi6x/nuttx-config/Kconfig create mode 100644 boards/ark/pi6x/nuttx-config/bootloader/defconfig create mode 100644 boards/ark/pi6x/nuttx-config/include/board.h create mode 100644 boards/ark/pi6x/nuttx-config/include/board_dma_map.h create mode 100644 boards/ark/pi6x/nuttx-config/nsh/defconfig create mode 100644 boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/ark/pi6x/nuttx-config/scripts/script.ld create mode 100644 boards/ark/pi6x/src/CMakeLists.txt create mode 100644 boards/ark/pi6x/src/board_config.h create mode 100644 boards/ark/pi6x/src/bootloader_main.c create mode 100644 boards/ark/pi6x/src/can.c create mode 100644 boards/ark/pi6x/src/hw_config.h create mode 100644 boards/ark/pi6x/src/i2c.cpp create mode 100644 boards/ark/pi6x/src/init.c create mode 100644 boards/ark/pi6x/src/led.c create mode 100644 boards/ark/pi6x/src/mtd.cpp create mode 100644 boards/ark/pi6x/src/sdio.c create mode 100644 boards/ark/pi6x/src/spi.cpp create mode 100644 boards/ark/pi6x/src/spix_sync.c create mode 100644 boards/ark/pi6x/src/spix_sync.h create mode 100644 boards/ark/pi6x/src/timer_config.cpp create mode 100644 boards/ark/pi6x/src/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 04c8c210b94a..0431761e98f1 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -46,6 +46,8 @@ pipeline { "ark_cannode_default", "ark_fmu-v6x_bootloader", "ark_fmu-v6x_default", + "ark_pi6x_bootloader", + "ark_pi6x_default" "atl_mantis-edu_default", "av_x-v1_default", "bitcraze_crazyflie21_default", diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml index cf42be021321..5468e51d2049 100644 --- a/.github/workflows/compile_nuttx.yml +++ b/.github/workflows/compile_nuttx.yml @@ -25,6 +25,7 @@ jobs: ark_can-rtk-gps, ark_cannode, ark_fmu-v6x, + ark_pi6x, ark_septentrio-gps, atl_mantis-edu, av_x-v1, diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index c2a057d68669..ef05fbdbae15 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -181,6 +181,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_fmu-v6x_default + ark_pi6x_bootloader: + short: ark_pi6x_bootloader + buildType: MinSizeRel + settings: + CONFIG: ark_pi6x_bootloader + ark_pi6x_default: + short: ark_pi6x_default + buildType: MinSizeRel + settings: + CONFIG: ark_pi6x_default atl_mantis-edu_default: short: atl_mantis-edu buildType: MinSizeRel diff --git a/boards/ark/pi6x/bootloader.px4board b/boards/ark/pi6x/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/ark/pi6x/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board new file mode 100644 index 000000000000..98f6300f579c --- /dev/null +++ b/boards/ark/pi6x/default.px4board @@ -0,0 +1,70 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS5" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS2" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_COMMON_LIGHT=y +CONFIG_DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA=y +CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=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_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=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_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/ark/pi6x/extras/ark_pi6x_bootloader.bin b/boards/ark/pi6x/extras/ark_pi6x_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..ef4d19d36c9bd09307b24c6b50de52290a9c1753 GIT binary patch literal 46152 zcmeFZdwf$>x<9=3CCP3ZXnH}?3pB|t*fvE2En37&NW$(VXbb2Z1V>Yfx+{!Sz!_Ag z1d3W^<_uDt;o{7oI3tQmQ>e#^wH46uGM>{wJEu??s-S@ubcYtQd(H2=66(yT^M2m< zzxR({KA)Yn_TFo+^{lm?^{nT*s?$iOh9knO?Ek&~?->052M5U2U--h|tv~&x=7Vqh zG~USyAJ4XZ+ZVIp*V02080n`k|{J!c26!kng0Id#8ivIu{#{KEyP01 zMETQjiaYfOZ>}jOO3e^a(guif*C0_=547}^{-&jGY(gCXA4lEk=^Lnkkb4XW~hUv z2}m7)h-7Xh^oc&pp=i;9J_}H0Ir{Amv=+&4;fFeIL`gpDIpmJ3{h6go{TzqFqI7?z zA8j}=e(y)xGG=W>nHeP(bAso%Y5=4N@OT_ny|5P8!Uad>9 zqg+`gTVGX3XKNRC+vOSinO)56>;P#Yc6O0^{c|MIZYQ%@PIo=aFttJpAttiG(3mxk zm>5etzH%xIcNA%+`-m!-kE#Yzetb*6c^@e;^X?Sy z@dmoW!=XP%=7N4}YrG2kl<3z_Uj3Sr#U6$^(-7-qJ@gw}bNIr>dSXd0uD|^F`nXPF zaa_uozbq>Ox!5ct{)Izy)|su$uFVei)b7iVSDg=F=JS}k%Yo=q=G3x+udY735_xvu z^26(yuGoT8|5EZ^D|3n|_}h0S-&oC%F-k$H39$gjKu40N0S|$D$3 zvdVEy=~A|b*+P`dYPQU5C(0*7$xTGem8~9=#MRp{pD#zoF1g03@LWw_a&44S<%2rW zb(xPAYSBU!)>Z8^I?wT0hQ{fqb_Wf7MsDoqT+rj>E|)vwJdDT<^8LvkVoLA6Em!DF zpJyvbcj+U~iDK|v3fz~=cN*uFMV|Hr*5hu%ysF6Eg~0Q8_9XazCe7|8Nbd=TL-?h@L!N_0hb<^0axZlq}_Pd zNPA@}rY$UyIVGN3oX!Oc#PYmdWRA+mZFUU#X$fO7*4m^}#XB7oX%c86F4LriOj1d- zpUa#Ml~1cfX@i?s48?J#R1Z@Qcb2{- zGAQDO1u;fm4;1C@wunYlj-cK6c1Z(Xik+aJq(-b zQ3FYhG{E z1lLPJhW&T>Y3G%UtQ=jJ@0^;k8`n$0EH*1Abn>+N!WX4ITjTzIE>4-R^0V!@rgrWU z5bNeK2$`Gy{av)*|6lr-l{2%8_7QDnm{fLlX-|@KSzm^;v?tkhe_w{Hv}eNH2l_JR zmiAmDJ=m8amG(?5l>0IYOM8q(m3uC4vo?(8wrvjWSpzJjJX=qLirge`T2DINJ;g6VFMr+L)U-l}TfA3Qj1Eb9$I5 zf6%?rU~OY>5><8ymt#C}k8W;{M!KdYIU`wes{C?`#P#xeT~1Qxm%>U#r_&9wj+^aV zj_BId!rw$oFgfgr==ZEIrAldjy_eMqH~r;2dEiWd%lTWU5@2#Z@~2cW-6UtoUsb4U zr1TO{fLc}zU^eCuB}LUp;KGztwNzn*>mS!n($5qI`MwN?w(TcsCNcW%QZsFwZ+jt= z&*ujH7~2iBZ>&mWp*f=wd-|(H89zv}UTHb#DqQ0EJ%z}_O3>;yu%bR%C2`wON^c+lpfzaj}dRaeT#(; zuF+bnY8r{z1S)b@m=leb8;iwX*rXfXH~=6AL`4hYSc)2DYX-{^(oNS?{OXJP2tdl5sRdo zClp<2u&Xoer1t~j@H~Zm0Q1?rQkg)8(2rN+iLeQ9{wYgn)OW^|EKqH>B|f&dm0cij zFVwnIWn3PinOHRLD}hvrenZQT^_6}vP~PQ7==%+z@8OVZG!F2Nci-5^OOs^me|f~h zyvmuFI-*FBQhqyPmWYz4@{+;Fn8KkOMp=oGvheJ|5fgB(f0(vag?&da{ipoCJj?fM zIaYqtVes#1dbX+cJeS7@#}lF)R{5YF>3gb4YCczG=ag5Q-X>%d{p#Q@vHm8W{n z2SR`%9(CU}LV~ecjbuaqqH2z`R{$7nP4vl^BXpnU>Xl|)IU|ywUdOyz^GJcjDgP5@ zB%80|u`@pUO*nKQJh7YENpdcq9G}n307s+j2^XM-_eYFP%&YW^x588=Vos8*OKm2+ zc}t}&_(q87zXPqZ!B-=1b`Y$3BCCP$1&upRw)!+BiE?67>aUm?shc9JuZ4~Q-S?8* zhQ?I+urCqi_BBzS@%uC1FkrF~Ys}|FOxhHSQVW}+ye%;qnwi~<>t+A90Y-UZ zI2ahK_fFJb&=~L5V~(n@O7@NH_VsS&z`3(lUE6DNjl9#rwXIb2MAw}qIhTu`n&lOq zBg=_tkEa0G!~mOUT{a(Ao5nNk;KjTYa*AhFg@(p(=u()UtU0;N!6_?8c@M@n-y|8D z3mUI+r_1QalRxASI%!=E#LCrj!Ejz$1LxJ8A|}(aiw%@JE@&pAX_*GJreYJL{ATFj zfQ67OrOod6CO}*5jlg5Td{b)lX_%Wd*k)*^kbD40v=K;hqL6^+Bc|bi+Bi{4aci-v zCduK@P2qUo@)ff^?Y;R4=wA8 zaP~w=fCQ8sHc4u;S$=2*<(|F`SmcWoGX4VA5FIO{+txTqezHCs;=?OeP>jD}^sJM& zbK5epdSmgm2K+I%7y1I#na)UtHf9UAms5PB%nn*QiQ=n|nMCs|f%QbWPUV1WU-`qK zUhH$HueMXrSQ8y#i`N9{0)6ma?E^UFht~Kkk3H+q`njNqu{8<6*i$2Xw@J#Bg8@$Y zVkA1+CaC~p$30OK#kucESl~UC{~U?pnW34r>irZme>kI>;+_Cwy@>tAfc1Ie5NT=G zlgz*3DgZTOGU=M)lm(-vCMMs6eJF}01(12@E;vq#S<6e=2V6Ezv5zuYI;onrL#f~Q z;1SnfY0z2|{n=~zU=j9?>`{-;Dx0J;_b->l2Z*?58KcY_iqOKT2fJzdvYfpZby4|^ zjuE6sI!07_6dy|R86T^42>xRYRHDrD<;aUY56L?{-GMY&3H$_WY{++45vR-z0?4@XA8(Tn&SPk+e;&4Am;T2%g+uR;;EUQH8*Qys@PB`NUl_b^uvV?5UtBM= zF(-lfS{o>{vSFnXr~Ti6xL#xB{5;k#QEnX;*Xyj``mJjP>jgi3(lT@|KZrV9>3@9CjLS4Ehqw)bYVP1yBbY zTL<`SxIbckpI-IWGl1-A%JV**d46Jn}`&9JG}<+^)Ln8)bKoMsxo%TEl8t8`LwJowg^o7t$8_ zof@=E*Bxz>(hh#>9O=u=HpzlkzpPoh;x7Bfo;Y@b{mGs<)WIp*Va={6B?*TvjL`j} zW_Wj?s`06MjkLuyUi$1jKZ8?>2YIQ@N6a7AaL?&?u+PQqV4jQJaSHFqbJ_SNPt}0p z(mg42FiXMx*uxvNaa0uRbLfP?<30T&A7xD|~8wt)!8jlcq}<(kV4-H&M8>sYIA| zK2*v}<0WS64hi$|^baxkv^u;Sm-nPf%802`B{pVeK}mvK>loK%kXu1P>IU*lz=3DY z^@khi9Ao^*tZrsng8X(1GliLzZC|LG>$%O z7sX$MLu7c7#6@tDnaSAR3?u-{iGG~Bm?U^oWx!3?-earY?OhtrcY*2+e1z7w1;XOTL?q9LY{@c}ChH z=_HalK`NGvmNlTiQ$~uUr`2D9iW^6y^xF^RN^E|Cr0w0rfUi)skP9~nB+J!CdWG1% zK|wem@wc=>+$}ItPb}BE{@}Rg7?bas8}zSKwB&rit@5RiUos${JjW^i;SCbA!z9H7nHWmL z=DFH{>x)ST#dvZoAc7Y)jOp6Gw`(wpLmk`03L2BZmz=rE0kILz?fIcSGGhW%2}>#$ z%L`PK&E0fn^PeiCT$12VkoFdaLw{2lTdm_;KVwn@3^0>Zelw_ErIcU!e;OFAN&t=*O_UNic%x3@ADh@miFSUX8uQ1}87`4Ya^q2?Kw zygyq9{iC6h_o#dll}oY!?dvMZ;!fHfLi07?@rY?KP=ImzN}kq4VWg67IP~&6SyGug ze)btpIP`}>4djS$XeVeUt2`Y(55CYlm0U|TW46JHhtryx&#Cz4rgtc9&jCfDl%4L- zl(Ksso*;EKu=3IebP;_m_XKZqDlEsX3WxqHd^*5U3bcXzfD?-?F~}Ytv5xPG0q@V; zlxi=-DmD5JgYP!B5Ywj-z7jKS8VJy}O4ly!hw(tGTu(Vv%DH?`cdU1lDQPk@o3qCi z5!tSaWl_EJp5;kCI>yhBQqFi5uz^*Q!o&oQIzkg7wBX;Y5u((O{$q`htbEwKevH52 zY74J~SEV)7IW+z#2f0#tmJ~E|wM>MQk8<|oKi6ZG-QyEi)HufZ`5@N1vU?DGy(BIp z$`hl}FNx{PK&IRaJeojGfo`pd;B7e6@|{E>ssE5Du8zg`Nrz=OrSy zEIJw#8}ZF1%n2Po%q8W>A{_pDO-_tovm&RKnUUC#<0Y0kn^?eg{nZhme5ndqJHoD?|35^Y-m}VzQH@mOBSDWY_t7lLICDBi{7QJgBjop(SmmdqytIhE z)v(u2yyMzOO_DL6miQ|CCzP>6^d;f`xpLvo6gX#cLn?C(mj*9!ks;z*=~ z+I$c^_Pe-_;u_dTeMK5^YX2M3wM2bxpRoGD+19GeI^HBEN<5{g)*G2Go`D5BJeRra?;#`*^w zyRPVL1FP%~Q!7kXlM#JBHUf>5$USOkrhMQS?2tiz`R`;9j8k|FH~-(sAguB`;QUzK zbUl&aJPlp@{>pAg0mK z$Owb~`jO~+>=rgw`7lhf+Cd8#XvK*rlq7=cZGhy)_8#FDt!;G@Na3*j3PYem5e^{g4}?Z|Q9OGBO*`Ids!H|LzY^Ddk6G z89G}3kP=A?Z5O<_^C=no%k8BK8HUM{cpUB4FENXuuceoF!6Jz-e` zhd3|`+89=u8D{c@nQ^&27zYjIb!wvh&`1TqivI!c0GSs%46A%IN=z%tsrG^HR)$7b zrAZnMy$5<0#kE)8jmnLB=^AM}xKolftBvH`*haEvcA+Of!UsBKsv*2j%_wH_ANGuw zKT!4F$xRd=GDdT|ZBia~(jD>wBh!&0Pj7n3k^FgzoZa+tYEtoqfKiH*lt8V_x}v%9 zCE55cY1Gh7=~iO*4*3s`mwFlY<&>v{vxZ+W`Q{K!lx zKBs)f2g{KO_~zT=i1$Zpc`;JUB42DVtDJ*o%HxU7XF;=3N|VnAc&y@MBbOo+I0&gX z{CC<85p|8w)oo$SMsWE*8G#;5)S4NSRw)~Sm1w8d%pzZc`l9j~U0**A7q_0D%~|6* ziSmWYi@JzThbVth$Dq)`-{B8~A<&h7$GdUG6l3R&Q2If2sg&MP?sbAxR+0ft0j%Kl zu_>#IS}Xm6P)W5m`b{lzg7kibcctT5(5RPmZjH21oo?WIk8){` zb?LYc%D3kJqM(^ox`qb>_0V5y-0XTo<3e?Yfd{63Jxn0G&^e*+h*I6emL$mx?5UJ* zJ&Sq`jd3!&?tm|S-8P5z*kXApw7O)*B9Gun>Q2LcL+=cpB5Ql`md+C|D#O}8+}sro^#@46mgyt8LK=bT^KBMF?C zC3D%_pwMUP;mFD!Zajm$vxjh2&&oEw-<}6JZd=g?=x)=uuqI;amC2x>jPKz%qw}2S zUC6x#zewAR`9YhlF=#IrC7tt&CNo*?PSjU{npPH}KKshTwmp}1 zwyQ$E&#oKPUV--nHyIu#!m_CLj#5~)hBf~*z?qi>i23dSm7uF37yK^3n4S;78zjJr z%>hn46cEwIUn4Z{Y-H|Q8^WQCmhgq>T#xS*=v>2VOXZ`Xlp&oMZxYMtt~DCEYFgjPI?2lXQ%iAs4((Yh8*S*~6GCepNa;RsPmoK-hjB_PeFbq(~#70q{#)upK@ui6x?ZMBQZaS{B0!u`wZ3%6cmZvR?E6+yuLy8lB%B8q84ic;)e)VwF!)DLJ zCMl}*{UKjX#4Ksg1DKD|sJ=#NbUqAhr;;a?RRuNrj#(*Y!6`z{Eq(CrFH6h z5|hQY30X7!FCK8f%P`UcEl=uHuV;>I?zhh$?}Ju*{+z2%H+VMCr;kka9amrQ(0ATP zHh6NJ_{Mg&A=N`UEv5PWJ_l=7;u$+2iQ!}P3C^Yfn=Q1UjipBd2LOrha`#Hy!*lT{ zaAx#;_*>`0HEKOP_M8vXx^^tBDjdsqR<`!F;thEDhuhWHp$(VD-^4=WZZM!%&`-Bk{%2 z@=ZfjzfM~0d;)2{jtHM>ZH>v&)Ai<#x)q5ll3Yty>{)iw*Nz&&&%fFpsZ+C+sXK#O z^|Z#BM0sYYVueMDEv9deo;S?2LPzuKAssjv3hP(Uh*5il4eR~c@7kfZy`NT6-e!km z#lxC5-{lSKb6}@6Lf1laO53)n)i&+`V=cw(>03(s$!c&d&TXpKV34S0*KQ_edcVOy z@30rnq4!S3#?^V+)lCLgaSTEu9!QbS1RMwIWKOX$wrtT)tnA5l^#w!FmxP*)ZAtxP zeR2x}zIYQ_tdkAWkv?zICe@34SNtY*1LW6R29K(n2(_AT9BmJvoS`SOyS_?gw}-c> zwPYl8XqZ@NE+Hbrjf6I1zb(MrXp3{C=OZOHhN1Opiss*jUa+8fhmFz#=flZT9on(_ zxQBODT3{F1UMNaN3080OK%|8zMhy>+VU#h|*h2Y6L*rJp-j*!o`3!)qCv1Rrj91mgh)lP*cSa#{ z%mzdoPy>bH5u_A~pCOGxAtSfNM6q=t`uWR+F+S+T7cTTkq?j=T8Qr#2_B5O7?4?QPL9Vieii6&7~H~#9njbI9~V`md=phjgQA>$w;!uJL% znU2~%%rITWW8=cT2Ok&>Ln?u{>l@>WW$;b&RU*dRo-VgX0G}=%6s8LN6rN2$}lKB+qT);k9*k$67sPK^?=E z5a{C<$a~5R&F{j8-_Y24o=u!13-biowkKw#3FbVFRy68Ugh zj$8p7`BHhgeB85&<2rIGK?UWc@|?;F*w3|)C(7Z+126a)v{h|?_ajSX-(~Omg_WXm zh%>f0QSZX?a#>#zC#Txu+=c_fqo`SXdp4f)#(lhyJ1kh!*yR#kG`i#3$1S*E~QZ~w)U}8 zOeM>me&g|b=27p34P>hKTF{B7R=q`Sj!!{;Pq`!A^@4-_92|C@t~-O7sA^lOq?X}l zGW+lPxPfvUcc-Ve#TPTZT$0|*3~4Oe{fz#|&|n=j3u<-P+q_uD2cBcUQws)FRs1 z%ih%`@(X1VKK}=t53yiWtD>In5qv%9T$`SW`C&OX<}Q!gCU?okLOKRj2VHB^r=m3t zH%~jHah;W4ma5+MMBd>m3!T-4PNwAeqG)+MGt-(_H-nneDvgDth1LUkKw>K4S>kh7 za^+l;vz&R`U8d z`Jj5QfjnoHelPREN!;E-YIhRXIYE!aHB=9=QsK!J=&+PVzS?ylNm|BCDE;d0>-Y)n zZ*oa@6t&D%y!T&c&vQC^HaOu4$v747LeM+snfcD@!(LG-*gQj{1`qbT^Y2+D6_mZNpjpY;BkJL-as5q>b$ICeJvYt`K>`&jbX+34UyzXP4Hrvt(+rS_b%(nYsC3r!CJ|i^C@g97nru2;0oNc(g zhVrNBX1CMg^W+&_N^`b!KEPexx*As5Je~Dxf7DVyOhNDlt-hu)8yccG=sruorrtm9 z>KI@FNiw>q_ssk2;+#j;MD0fKb3%-d0L{-hD(Pb!xOL@yb2x4d?G3Q|M|_EdqBfN; znBx;+5o|>+S`#f#ZG=>&qV-TuTXz#IvnF7{0Jt5W5&P0e=ymut7$CD%(XsgvuP1KZ zNo_($+&pMM3c7Uqj&_w_q%q9}{!M`taTM(_%7BV=(UpdXM-e1I+Fn(oyPEovF45`R zEtQL##OluZ>TT0 zfN?vw-0kdn-x*g-6px*A*3B2ImoSSLITYTp7(zzkHq6vb0Z^w0sS) z74vPN_?oq`UV92wxne#qR^IMlwhn$y<5-A6u-h6r$iu0V(o%Og$mcf5zDN3WQ&^S1 znN_)ake`dIf>qgjSe3as3G<9`#CICE7ExgaE8>2v6b?j%Sy5wTjEzL_7(`7;Qn|*R zQ2DWz>0o9L`Z?2ZsO&vDCiZb0u`4E`DbczO(npd8~Qr_Wj4 z1WEmKSi+i@FeYh7S@cV91^v=e-GMgQpn+j5&)R9* z6pjz@EF8KsO!4zwI**_;0;M&W6N)PWE~QaZol*KTruS}6A|}>jhsD4oy>I;?+{v?J+9Tg^XFFc)f$D*QttOPyN{d*)Lbo5pcLJiE+@8?k?4zsvlez4bu*U9fimSF^KIzIJOXdr?^X)V~cvzw>C8N?um~*c})o;9#iv$%~+X-)%=3L1SUznfxKsOr0Lkv zQe4zq{~v2qYcuFi|`YX4K+tW?$5 zDsLY1b^IO;U09u@2;3xpa;3Zc<|cZ_YY(626JlTy;kwHz=ad_z`Q=ebyb6+#flrV) zSYPfB+oV2NQ1_2eIWeBl_$or43Fns(6XmJkAyzPB9_9BBBNq-`JK8N9u@9T2E^uq3 zV(uN&O34&(KC$4tV$Q4)AB`E(6xpP|fb*jGhV&(7W;irybi4YPO&dH)B3P)*<4iZE z-%yKZu-D?e2CM_%*4)qPuvJpLNWQEZg6@U+r$RhRA_2a1Kq+?p9JsfIl zVXL)83z&pO(E21K!0&BwHI36<{PPHn1PuRTx zWVI_Bz2x%NM^`EmL*@MyBQ(bcJ&^7m7}7Jc zZmjralH!TiwDG|SpdR5+@zAX9gX+YpgKCQ5pqgfiAAEXrn|e*F&~Qz|yFq>Y)Xw-z zg0M)BpiUd+rpkm>e;quk!l5@tehsVV`hNF*245BJ=cJ{5e3H0E2~1sA zrCWdbiTxyJegE41(Yg~+_bvWt&9gdxyxzZ#9t$iv#9Yt$CB>kfy5`dWd%fuYv?1U zz1Pq6f6x~@flQmzc3N%SkUmvA6!X;I)ci*X?3yb!{8qjB#djc++Lfgn{-)X;5& za0bA+c!Pb~K1mmxMD{{AX^+bo+#F<{3x}=@{;4+(wB+pIZ$U#?OM&zdcG0JheS;QvD@ z=6{R`q9yY7=YlTC=>E%Z2+Ws6>>7JjTBiw7mK(Vjv5sjg*uw@tMzjXS{5F5Oi44Um znqCrn67a-ce&O*MO*>VMjl%RS(v|>S|HPc-Vzz`sUX{LMw$ss}{;IS@ICOd7^}s0| z>4=WV*{>v;kV`vxCqUvd=B(Mb<|ZB6A&9j0A#m(-(C2XI`XNK)Nr85J2e-@J#O|WcDNF@8{U9H< zxXDA_NC{>a^(_{H>B16$se8(Q_t(*JKOTWDZs>mkw7%aB9R9lCnbF$W@(rm**PD*L zE!RmIgHNe*BJcL5g+osb%zCEQ^@=KZ-}>5AvS1ynD69eWrvA;SyaM|P zHNgqM_9q6OADDpHE}^SYO@p3$`8rBDDLy^__40MBMGfrX*Iz#VMqCM~-Yl^{48B9h zQJxT#Zx&tWPMktOd8OmflvY8v(7N!r=bf+Uy#6!qQP3DSuiImmIOx~57iu7X67dXl zt_97HLOvQ*8TjWwSFBQgrVl(B{k94`FqKZcQ;8UrpeYAWC1~(vSFJ4LZ-=ZQXG=>^ zYg7*U*OHH#&Nd8(-cf;>sQ+G7kj_V}Ow_ItZNqx|IhkswKMMc2Y(mTytdKeCqb9wS zy=pkL4LP%9k%mJL4oz~0O_X!H(trs27+i5UO9W{a(jufqNM)ol(psdoNcSS$i}WL; zAH~6j;sJ*TzAqV9KCX0J#w^$j5bf2eE?>6{*tUEP?fDqYbZmc9qQYXJFAx>78n}-c z&|_Wb3+`ryI-V)AUpo@&AFYKRJQ(@^X7uShpnnfPjR?^GRn&Go9NIsyshE{G34E;H zp?cC7$>ABb9A3jdN-X*zHaR`--eoEG^TD+m@FaE@IOr8s?G4O~8ucFgGG#rl%c)U| z>?_u;>|^j|k6Kc7#!tlbYwc4`Hnggl<*lkMA>HOxO=hpEH$#J)$mDHRZ<(XB(l0h5 zw_6=Q|D2y#DvBu%v?7j}L;N=NgU)ZcZ=P4Y@Af_Lfugu}#>1J0LT`+Um56%mVr~if z#Y!jEx>)`b_g(WWmB&D7qp~)cG8Eb|x@UPZ^$f_{1FQ6FswmGeIh9sUL~R(ag_OTN z;~~oLp|>FS;-rxRItwB&7xxA9-WfSvgcQIACRQv3x5VvPS`1x1Kb`&yk$-*U-w^pv zj{F-zGvihGS%#@*6la?(3Y(9r$&0QlIjZI_I*Q$L8qPLJUu2X`c_ix~b|26`lT$V6 zovPs;r)o^Eb142PID;W<$}CQ&rE(*sTqF~v=Al$BO6fPF)I@i3(av&;dy74HSEiPj zmGyJX{p%Q9bIeMZLFAx$aruOjo#h)WJ3XVYJwtys@F?|Eu@8l$$QdDVuM0$vEB4J8 zG7SAcT@T$zPk@J|I7W35-Bcc<7ie`iuGryvP+&dTi1R{Xipf^8tH!|`|HtVd+zEnn zK}g-Dt0#Q)V=dD&KA;VixFQ;Lus~%Ia}96P7ULW6M@b@?(48WN0KR#M4gcr+w5ET( zuey4#Mtp^@fhBXXstIOrbZaE#X3iEvMSXE9AFx$s`aH&RjICLX?a`lKh8V()9ngG624?<;B z<>0H?_jxE_l6oR>Y%Kh2;+jT6d)}@pjQY)JBth1r?Fp(QUDL}ZV!xiSuTu1-$O%4^ zyuqP4zRhzKF%z8cbND-?O1ltiSby0YuRF%YKof5zo$&RwEfEF+iO?TLqrqPVZTxe1 zd&HCQhc@sI)o$);uy{UD?Q^Jxy{h?6=+IuqSX1uLh5Vfu;ZKZZ@`t*l_D>fbJI`v9 zT=gEo_c!@NPoj*sdV|Y_|HU%=5?I!`*pn*JIzCNZB)94e?Z?lvh7Fz=U#I+$CnZu| za2Y-GWkz8b#yQ`U64`4vV2o*mb~v;KdJ!$+u|dsieh4qIv;opCP$;{Z!b@^zLH3y0 zrVCEgOi|)B`yJPJQZJ@y;YN(hjAL}ycsQ(uMQ2mxu+JjzkzaFUAOBLW^TheSluvp@ zc~M$?mi~n3Do^puzuhy%Gu98AwAd34%?ww_LgdsVIu^9%O!yM3%~POJut~YNpBH`? zqy1SRUHWgFghDydKT>P751y~)q0r}ur=an0LL*jfSnws=uyTrq1A43*Xf{1@@JV9mW`glKpZ>?xuzocIaU>Nk^mnnM1A{85b?qI!=bNRQf1a-#5;ILN}GLNUkzeV zQ{`9>EfE9y?Z!K+k9z3VIR^doyav>R=yCcT+vM;NORC2xRTajO>v&QrV`jv zsrO}7VUi~lSd6Qn(Fu&!$U@19iC+z|(~a;J)s?gw(Iz)12y3FUcGTpF#+i^$cFw-d z5l`&6bl@GB=Rlv7>jrW9gJE~!P$&<+wvZ%Bxnqe9te0xYsn;$&SLR=z!>2A(7`_HQ z0DZNE0$DyYqQ;@UYoNZF(QjzXci+`m5ybF>{}C&ak^M*bEKoZFC&xK=ws3$h`prMT z+59hW=xEVV&B*?J3z0tp1!AB#qOipuL_Fobg|Ofv60MF0jpBBe*_a(fc}$I*x6um= zE>>r49Spc5 zq6q2@Jtl2di&mP3$QZ435m8D`&?%g4V7;}gK2r83_~yQ=uE1LOrt+Xe7ol{=)eDuC zmCI5oURxh}!7(0>#baz-cz2eGS<{8*o-sJ1y(8o|K9;y<1>iG9Y^<)y^unc z4@tAr zx6+tAGvyo@i(q3mI6*xc;43}``)IQO4L%Q_kC`~P+*`+Et>bGVZlo=q@eGH&m?;g$ ziRzd?!l@48M(X84D#M}S_h_%jN#;sAXM0B&8`pLQ-qvTZhXBS%n@XD+h;d`hS629Z zz!Y5xe0bLD+{Tt9sV1_jx#^%JZhF?zjSGozJ+9;T62UQi-HwzhF?k7VN%o-M zkV?J1SQjt3CvR~GZAmJVfwOzkNOs7dm^u`i0S_N)^BNCM%hq`OJh}5%pnV^d*Fb{t zE~GntigN>2t*!Z02kU>o+$;qH%nTtfBj+6Mz$?x_A25M;X|1d(q&mvj+Yy)F6gw~W zj=0j(YOePnpk_p?hidAulg&QlxP06>x9`~YLf8dCx8JTO0=)>BESl;XL8mPAToLL+ z`H#5s-@wm>Og*J~w$wqpOtl$A`L^br;FNg8zUQ%ZRyh*Ye8Z>k4xI8u9gch2nNHub zTZ3(&k3y`aP;yDP<<9GTCuohowJiy$DgNfRcY2B0@zZ0AmZ$&vi4=nZXlMLZkNLHE`{ei11_xP4*VPVV}XO0$@-?_ z?*t!@&p~@@;;+U3L-A&RX1{mY%MGr6)3VmUJHedzcz?I%Zj2?{A@-bE3u}S(l@vW7Q7$5{m&Ec1S>H9dpE=?r@4jDBYnK#Q|b5aB`UwG38Nyk z?2zaf6iLY~b0AZNr{ff|VXw6Pi+6$##INtK-XANWK3BXsCa8;v&ldJ(E4sL>mU#1_ z3v3+X>W6+$&stJqSSH8O_L9!oo*X&76Z05Ts+eMu6n(t2jkc8B!i(@Ecj!-=b+7bt zx|sI2C7hE03ckJY?I0tl{##w-T3V9Fc@f3nj+h&^7t-2!%+(_$u$#m`;?}opLHyF6 zdxe;oUO{Wb>ZokGSt7Z1`Zs0`I98!RX#7y#q3D&0aH?J*|}}0K|cPvuB~%(Pg1O*eP_FvT|4Jy zos0#P%&tAXf*{h9SnA$t$?54?tr3|#3N-<4zm0Tan*fi@B-bIw!Ip3;xi(peiBI>> zmY~<(Q8fAe2IjfHK*qo+E(KlG-(Khpe5oyJVe-BX(6Qj_wiNO>n=%JH^A(IphV=ar z5n-8blKAeJV0e}-GI~~-mZ7CfC3@z`f|G#jv5ycz@LF#S%i}y!T9)6j({W>qu&-3H z3CE3fs>ZuI{h7HOR%80fv(WuC1;e*-{_7$&a)0<_Zk+%3>J-~dtEp3qTqd+k24G96 zGF@P9u*y^;w7qanfTo(Q+Y9N}nw>iTfpl5}&WJ$0(3k9FW^jLa5B;1joC%oTB!UrF zIxf;04x@fUmNY$katp0rgx}t;k<#zzI9lafPO&$@rW6x}>7%(;*?cm&pWH`hGr481 z`F?mc(mCS0rbi$=p`F(8Nsz=&Ge_s!W_~9a6F=qi=p7HJV}my4r2w;&;#SGr+LoAL z0ZTPl+gfbqhg{IT4b-+Is!8eF3;z=6hGmGk;lluJodqVoAF!H_1(@lt1!H4BZtw>_ z#cE-MaY0iI*3#@>BLd!{i|+td^7H17^GmJ+Uo*Fj;dkNOmwR>EE1lm4-c3;h6rL1d zF0{wjpKD`o`x>ivSv=ows$fAyD&yDs4_r2_tnkwnht(GIsdPf+4NIV<0WG+jWM?ae z7%if>i*Z-pJBP^t+$mVY+BQ0FoWBfl9ykNaE4&^H&pVulGQg*uZJ;HXZA5w7o2@Xh zuDKbYe%?z5y{=0J7Id#KriX>jjq_(K2{EW~FctGnlsCQLG1!M(iE2u&4chZRcysz& zOL7!LEd4$eYtoMBoK$FnwQYwS-b+WlL#a3eP8e#~)2of4Bf7o&Q)!O|V-#1~)BVWr z+m~u~b%>g~TI_wT({Uw`27ANS0PXRlAM3HAjd>@yD4zClE@=Ns?qowuPGM(^buO$X zoN~t$7k(35t{Yy|#02@c6FB#Q=^*AW1E6ZkkFkU1@87VvY5)&;zh_PB~T9ZDlZ1;n3#cV_y|x%u_HTOdCeM*dTr$ zI0G+;;{Mj+(tdt*M`TW?m?@q_cQ@ehR|34>T#_RoN}ovof&aS#sr}wk#t%J1H=Ebh za9?1~B`urU!^Yp%zj%Ki>Yx;WQa$*@VUNT9+cic-=xkU(7o#hl)?@H9H@q*sI5+$A zy}dlyJ@;)y!)jgg4l%p(T$80WU+tD|L3`vrZIIPk<>Zz{=CzTveU`S$rS@>~r`uAY zd)Ee;$a|~VWJbOB8C#~AdjJb-)h z;y?I}VKBjO?)hSs#%43q{dzF;LYPcBlmb3UTKve(kKE#kMC|Awj4@uD5iK8)1-(+-3ci1AYx(;qM1y!^R~h9^wl=$^pa z$QPOpGRO_re^VIur(V5=nJvsZ07}^FpW&O*^VMo5FV*#1=)13xZ1Ar9kgK~$p0ItR zi~Hln9MtfaNd0_Q!#DgB%uFwy>w+5Lw7MJTuk5a$f58w(&sc+}9QTYwwsfV@lck+F z^JD9&1=13UY%hj|`A=aIwCV3g1&x8Bvs?!Vnxkhp{jfPH9X(vAhvL=mYR%;p}5}mevG}IQRPw87@_rl8A zO;lS~1%1r2QGW8dla~V2hyDEldS=iafNR`IT9WEA{x(2zJ5T=hs&w}hQh(rY=e1?i zQccqsf5!Fcoy`vHY%RASs^OJhP0V2EzLCDlhDxDV!&_Z-j=pmKSW_?~KKVqcr0XVT zTIUC7q5tG(Sn)SOhNMuKAq9QV#k*d{o^T{U@p+)lER{$K>d^s5XQEEGtFQcbKyqjH8XDnYZDzi?>5+mU(8W}ssc4>6In<`C6I5M?fWIG}OGc_cJW zAs+r3*0o8>2sqZmkkyGY2d8y$U9oP~l3K-gTh}7KKXS@&LGvEnAm01%{z@0Ls+Mm8 z6CiJ-8%ZW&1m}4?oYDbvaR;F1yWpo5iI_DsSAa(f`Ue9hlry5d0Nq9)ygO*(7C9Ep z5t>({-^`n2$}&?p)P-+#UCd0a%Ea;0F8i5X#3Xv4|Bd(%#@siQ!yDLu^Bm*m-HBLPi;w;@H@WD49*^j2 zoQAMAuW64gHnApNS*6Yp_fW6&7TV`zz{9#bJtqWQq>w>tEP7 zsfvBRQ-wdKa!2^I+W%6#52r9yomQ2tnByBhQH8Q+a4r&qy7Sd*eK_+8HZ`K;ZX_79 zIbm)KHC26h*$OI;ginS@B0 zjt%l;J`1tJ8&02t%o#U6A(`-IFYH{C!t`sFJ00N7zbv{E`R~L3x*{czJ_UUBOb#bv z@Mg^x&E9ZG8_u29@Bb=5Yd(urO64PV7d^X(gM{?b2Ash#g*9PhAlYok3^LGv;B+(S zH*umkeNH&#g)qj|w#PB4lidY72c^2bCa zZ;!DhLB=ns;2rBwP&6c&GuKPC3VruT$Q1UWWp}dV6IatJ;qT&ha~Ky~)}OttGBZ$~ z>cGF{fh!BT&AioW@wGdJoMxrI2nPT&MeBErogU$Cs^LS{|7=FP9aR4|D5dsMSq%K;AE`YS_o=s@0$+y4W$t@S8B4hs zPgCG%?uZ)>hp-!C1)QUU!glaK!7;M<-g8px|A1?tlQ@N)Kojh{(LcI+M}X%WihWLr zy;F((UrOw4h`mm0@ojPH&=)s5dEfIl-#pt(IkfP5ex%gjNBn2pKz_Oz{)H0mjn2|P??e0w^E+f3!H`RU;d!H{St#je8^r1gHKqigJ!a19kj)f zL;ry3MjP*Q`+?cyil)^)D`HlDLbN^Art;}A(_I2+HzOxP!d z^(_U@7ia{&D$p@H)V%|xKG`_C^Sd1NEN~FuH)9M?9Z>lh`u;ueZh_iiCM|bG- zA-atRHq2FTgtF?+tl-krZdIDjz1W4b1mU80y4?wV3RTZ{-eREWM59%oQ8=N{>=atO zM0tewg(#0mg*q|dL_*gv!&PkGgnCm0QE;;@%B3p{NNLdDB)p*6ovo`>(^W;l%{j)J z?nix1hXbCYXoAi%_i}4Fu)}wOHgePbf^tGoG+3g+HI-)<)(T>se{^Pzm|p)fcmU1_ z?(Rd@X6R8JsEvheaG1NaHog9}rF8BBnSAGxYS64N5%s6wgKdJG2M{+2&4ds)L+>Pd zE>uK)fHQlCX?bjU1avN;ueqFqY{?$vMCgcN-I6b0TCPD~*i%lS#Jk*tG%i$>HnOoF z15uP`UwYYS!lhZO`3L^P*-5%)P0HS>%B}^4!)=3wihbc7X<jgH;#I z{d@KTZ)7*5yI5+rTi=K`1(IR;=aa}5*=9VwG~6`@@^B$JWqQIT%n`ShZJl;Z9&0!T zY{#(r$oiLY&O%{BmyU3;#5v#-ADmVMu74SHH$wX{ib-!6>ci?QtqE?(Xc@q9Y)qZW>_Zaqq9@e1*3c=VAllBhy2g^&Q|h$qm=);d@46# zy4t){Z}pAg9dT@vtg7plVgd@*E2z~_jo#Zi`@PWB+RnM}p{;~DO53!1DcW*lg1ub?3$e{_X?G?;C(K8mha>IN<%>XHpqA{7>Xx^V7ll z@<#LWWSokk7vZFZG~q000m4NjE>>l*LQ#a zqG?N!7+D{S(DO1 zWy8TeYzE%YfE2YSMyvjYxK#UkFM7jM{GKS^D9BR|K+6%9Q+R^U3oKNlOQg15=dw+Cyjqs^>7bS((Rf>qVHysI29|y^0J7)fwwB>IjRLdUmB>9UuQM zkjO4jU8$Kl12Ze?RDGa2gb-$&&C>rOv#sM=D200zNebTv6EwxSt^YiW($|0CH!a86 zRR0{x(py>=)gI{2^Y@-J;8SzJNsbA>rqIeN-x~j9`+@c_{xIf7S_xv8foBU`_0KQ{ zR;xe5x=WZ%L}AcK-E0F^$%fT!MdeGACb;J&QlQ{-&fin9>Yre!}lN@xGDW3 z6RT0#wZ`|azqocl%lp?itvzw|L+2aUH?3Bi+0{QfiU0cao`#0k-g*DJb?tb!|%i9vSv?0b3e^w@|kBsrrh`B>Luho|JwTmhI?FID2VD6cG=r3Uw`V> z`N811)kg%6X*uhs&aQx3Bk9DTH18uNH<;;I@=xvqX!ZR|W9t)_f3a|G`POL%l=X@b zUw2y%RI_t$R&#g%mscjl@Vrl7WMk^kvjxzUN5LBi(UVGQs0o&w;U2wZeEqvtBj{1A zs^S7Xdzg#UI=kUgRdcBJ+mW`bFhU^`869_1xVT*3+m7rTLAQ z`X@9`-CQD`Vy{o>pK%XIDWI#_OD9Mgcb>QpRQ5MY?P-8(PPBrxwyJ+*jdEAkT5H4V ztCkXtx2|?j3*Wu&T2*O&?YjPP!!Ks0Q>FQf`Q;0imb;>-A^hsP(si|i>p?ji=f<44 zI4CP0aewwYrd2Mjs$I8?>#n+1S-#6^I1=uuszoe=3QrCPIy$+)5Y$-}R>u<;2WRt( zV_YFj?!Cv!C+r7cgApE>i?@RlM>-jx@pagXP%9If&UWBiFtff1YX=KGqknq-Z;Vgg zp`eH&W&>|0v?zrh5^b(eoyovT8XACPjxD({8**=HkbI-QW`qQi)4mm{M!9I7o%Ip4 z#1fqLpj7k`?V0Y}Q{D0o+Y#Vt9O)@K41|u%{fVkE+~jIp<=KJi;4misZsj8mmblx| z;)q%K$jX+LK%#LxvTEe2aFebiQ~b)wnIcwZ+hfu82+1Ui2|V!=GpL=2YMV>6B!p^bTc5+m zlBc-ekacyM68-oGWnJ2c;s*=Q0CiR9xU9h*Hr$4|gg1i~$(DOqQ!;GEYDkHq-ZqE! ztF+go{VM8=%S2s_2%z-FUv+Q3#$}-o8);vq8~=;K7TCU6SQdwIku2_;2HqRZjW3~Z z3R}DrpJ2KLYZ(mhF&$w=427I$j94Zz6YLHF(JmF&vCzTYIgL(^h_1et7wW46#m&IT zVc_G2=Axjqw~vkO!p^4%a#ljeCp`7w!6FCl-f3`+C${3=s7m1W>_BaWO7=bC3d z^C~oxiIVzHg_7dG%$ry`;|$IqM!9*j+0B6y-Q-NOGv9(9280U}`XPp%kE1x1BY|0ePD}QoUK)RLk%96ucn5n!{)28eAgiA&mz+6oBLQ2k8nPT5s z0SlA?$S0-{5A(Zv>UYzFSG-Q#zu<)Y1(23v9Gvk_UM}U|Jh;o`%ujoo<g2>qi@7HPJ2IuG}nEexfRAq zeCjNm;;Vc^ROwUqr%daABOm??My=5dF7{D*lX16mr(A2?y>f#$A?0q5c5F7qGj6qJ zc=93N`#Iw7t~rQ!d!DY5Ycrb(qsV;J&5S#zHQC3*oK(Za3Gz)-X8M|cre#^j>k5D6 zV~mmYNO2yJ$Ex7Z#%TL6{2TehIq8kWcc8sLT4cjgyLqF*K73Z21lNBb%+!p2RJYc&hQx%FRK(kedk0VE$ps+AVbd(Hh%42V=9!AKK9# z2!8JUqxJ7+e|*s(t4?rPCFSGmIbh!0g+23k>-P{XjZ+2s#@Al+#`uDs_LV+Z zn}vn}?wkmL)FMV%C3HZ@KEW?Oq_F>VUa&`j&YcH3_l#|ay!npEZkvGYrb^NGBfAk# zbvxp&`)~Megzff%p;x*;(4Zi@QR=Taqd->!XRG84=<4m5v)38x+s~|h-3>gbR$6^` zYa_oQZ5t(LIMv~Mu&)GG|LgKP-1+(lRck$Tq@iz~1f3ESJ>LN=$7fyiHgvymRz-V6 zTEB4y72r&2l(8xkSi4DWw8wCwU;Pi<{sioi!mz*IWz}Jilz=@_Sp9;Sj}_daa&N+x z9}tQ*%}lSK9((m)q_H3Sqfi>OKiUr(?3{Oh?Gikr{ZV>oe{_d$mtdb9dXM%;C3ug% z%}s9dmel_K=G)U_JC)fF`<4bv2+z^G}1Z;&B5PxyD0 zsI7Gd-ltMm18=g!^^B{~MRjHrZ`Im#)Edyh^195*Nh`)z^c9;Y>d zsDS4)VN)2C7VTAh3eQ!U9|*-7c9&ScCLpb&qzUMjcRG*CnoOHHx5;K=+ldZYariH? zP=^yZhTLq#y1RbW`xJjY;?q>aOjHtlv?naMV6L6YkWl(GHI0#abDl3eQoLZ`fZO|?|+TsgPqkmwxP>amF2BwFdY#6z;i_LXdKY?cMG4`hr4-)p%6fpPJLbs_GrkVbE90YaJi{G>8rQH1xmsC!U=&#m`s| zzgpgqsWTZ8>=>!FnX@~Gt;XoxSNZ~IE?m`YEiJWnwUt)O{MHNA!u2Jq4=fs7{K>`W z9O1fUUX@(2?v%U+$QaLACyV+SobONFbk@@+wc)gvEXd&8O8RrpyWWKbMrcr->Q;*f zK|{O_e$Iz*JK!=K*4M4KN6auJ{JXps6uceSNbhvpA;)nDJ2mBMHED^07a<*>GLNW=_1 z0oic<1=!@-x8}zus^u8mYxQkUR?G2D)9RAdudV)mb;6p`HC`a9?0;g+lZ&1l^Hj-G zEAXcA#Gry|Ie~efT2WRlo1C+K;ksY@)@rNeq|9o0w6j`HbXdkz%VXNA44q#9L~6 zxz+MSxJkxpc`{;5L5!(}d$5A~Dha!m{j!Pqtc`L*6>JI;t!+B} z6$_dZn>R8G_yEPSR%Rx4$w|!7$W1*^@rqU5l8c`9Yyh~#EWGU@g!D*j z0}Y4>s3A+N9CrfN^y>^;(>n4^h%B1`s<-eZo@ zrS|5BGYbs&FkgK4unq&Hn(0Xo@J@bE_E=<3twtO!j)3GK^L^f1iIKY<(q8wpk|gkb z;x1qa9Bm56$?X@QZ8nQx=eTi2X#1C;^Tf9lf%BBwlibz<+30ZKJVUPb1R>+iZ(3+w zh+3b0X)~~*gvjl7BX_3pq|BT``&SgpIBz~*@GBdxG8f?L)tgsE;(41Nw#Y*JoHLNP z;&KdGy0r72hz>5Ca>GW=E4+FxqC>?|K4u{wAGA_BvoC!q%tL!av)xJebRGHvU4_0t zSLba9pwGlW9}E&BY>;Gwbwi(vrH^c_s%U6GH7K@4mLgFDgIZVHFBu3uah{yWSi5@Y zRNEnYw#y8z#bo61UDPzSg-+2khCf0^*lmK&$JR8fQ5saXEJ725q!mmko`txGeDlD}QpB z*yS;x&GA*~TiB2COOFR=uFCTN9n?WkI@Pa*)+7BKxTS>#T`1@(K^njp4|#}EXbXYY zwh=m>*``Xe_908JBZt}+=$HnWT}Xz`Q1Ug{Ic3R^DlsjwnJU}8dhmYeRJgY{yole( z!2&1r)GCRinvZ(0L&}Wwg>)9oksolA`AX91rFURY2Qx>s2u%QUY9ot{%j^M`M0BI! zct+|q=<2|_4bM#h*FGb%5&DFVtKN*%ZZ~v$%$+!e=8J;TUxPPvgy}p!7cv6OL_5G? zVw6o)QB%iK3*9fuahb65!gB|Kbe#P)EI~8hOvvHg-NOCu{6+qLvY0zw<|~|Hu6PC# zfJcHwv~mfWojO;K^eN6xNeaMMIn`Beht6TX-8PNpyQJ^IJ*NA8HsC5syC5%h!F~75 zIFMSfoxd4_+TH+N7CK-5vzM#jMMz?1j&o(C$k2)4vhJ$LNa=P*;~ZTES4=I&RAi*; z++$`8$s9AC`IZFBasHL(HrtYllkIVKz9Pds)x$TqawejMa0K5$*wNVpNad5HUfeKc0Wh_*z8tK2&Z z)n~px%SKU}iQ*Y=seOzXCjvo7{2Gp#zC;NkLUsxGFT7Oe7OXc^@30Svd_V8X0WV^) zUGLh5-5SY(P75#-@|KOfWfLDS2UeUZt^kWQL&bYs50zPN(b-vCFU=sTcXTxNSkn4B055mD>%xh@C;{jAA8{`udfd zef_EKTYdf1#we6}kee@i*7YTj0Cw9~xdy|A-2ithc+*3`mn0j*j%m~mD|~8Ph3;wZ zsTOPMwm}nyr7Unq`ZR+;wQ0D6+{;6n40~`Q^t9$T(M`b4*oxj}`}(5lF<8lbjQJXH z_IOvT>UZ~{Z-s1z4QPdo_zKj>8`N3`w|W=p${oXrr63Ll4d(omq7{08oQ(6 z6Z7Pq`Vh?0Uf{DiUf{Q^b&l(-^U_ zP&h{#W*x0-Z2$0@%ec2Ggz8U-_qK8qu6Xxbk2U?lK177H;vAgA_Y83DFB}AJlFsot zo(y#z+Q?-eLcKKfu#6Tr&F_LAvu@7guqMT&>YEDeG!j0BM8$fv+92^p-tIz~O^44d z9ddXH%qS-(S6dfd(>vILvF-?PcCXqdhGJWO#12&H%r1-E&Y7p4gVp><(>1+93=!aYjSh`hO+6@?@PWN=?G#5q@(J@XtiPX&nQqsFQddUqGz4ad9S zbKraXo0i(QBj$F*BzlbOh@+N}%6d>Gfz~5_J=sy+*s6*6HYmM<7&LP+U%^psGFg8= zQ0Y5QPjKG%0p=RKTT|zD!2*nl+sYl(>JcW@v6CA1vnC?HiFC*5Si_Sk7>uCz?YG_p-INU?n=h==_~NS1}4k9m%NZa1VU z!l(PCjX;Kn6#i3&;~H4@^#l7}Wiq<>#Kfl(?NLu%^O~OOQ0$A4eI3G65X1$Iyq!)+I+_&?e(thvf;$w z=V}Y(v-jDtHlBbz%7lrHoN=CQ*i&ZP$fsh&QfSOX*yh>dpOU@vVA(BXn}og}Dpw9l z6?#UtuS~9JdtJBFX9)xP2u>6gTRb?4yb(v&pe~MZ`K1Bfe(4pNC{9WG0kr1XB-)b` z%CIE8_%G0#%r!AW*f-{ySYhC|q0=cz+5iqa&dAfQo#&<`V@!S8JF5PYH_ds)i_?^N zte~wUQ-(K7QYmUh0C%_y+Bs~_i?G293tvWVyDa@3<+j+6J*^Ygi_M6*BEuiXus9>Ay|`aDU|jLQj<&7=tQ-~8YxJP{I1 zwV>3ifrj-I=zTwz@Dt7+B4i%-2$^iECj3pRC#q8iB*^Z}cax*-yhO=lO2KJap_IXATzIX=QCryH1n%7NtBKU<14a_t$<-p>> z&AF%zU#}Bf?}av&{;B)IboJ9O%R^qT!fj@o z-cHB`%WU`-BRrMp{4a4uIVumRJ9NSV>I z24dcdJ_L&sGi=lBS|6vKoS$!_w`T_EKQC~^y3PGohfXz4=@r-fn;~n&BHn>EXIMM0 zDu)Co_HVXw`hF&l>nQqu=EvTAMRGDG-)d{|Qc7`w1f`x{4-mKQ-cI{_<3vhVlD_bd zLrA`tje6AUJEFHofLAl%t}^=<+Pl7qe)!vqs^Q56jX*~F+5WX{gnd_Z+{1r}Nh)|{ z&J1Ai6xjF77f}AV`~q91==%`8=NRE)1L@+-uISfe_A0UV0PC0I%WYS@z7I*(TapF^ zEahZV4zt#(t^IRYgiTdEKfeglV~%OmmvrJd7dKIrk^@PQ_5C)*$`Xk;B-=zY6O91*dVM;v052LU&zYi4ambxJrpBhm( z$OGdg(VvJOB^*S%^=Y98ZvYJvkbcGtY(t9NZXMo}fr-|dAS zCv+*<(FxdDf{NR=^)QFnW|E}cJ)$B#opYPhBcVskZBG!nov;igr>76{)OE1gVP^wU zVIa{&T9M51T;tF-mUP+M4GswqOu+YmT&xnh0-;k}ce_k>?8(#KhD;P@XB({w*j?tY zhkei?^yTC^Zu;^SncFk6B0U4&&4^aMOHxS8C(7#hNTjI`uu+6NwEXY{7e|;IX~&cl zNn;JU01==>`#g@pkH;q4SLx`O$3%JW?Xg?ux=$KcsjI1njb z=tle;Do1+88P8%X8++PAG#TcqDj}fG;h?3>Z9nf7zzJX}0gqn%2U=i&sJCxzG*x7p z6Fj9AkHtY3kDqTI;Zcc(gnjtVV)>{`m18ib*&qj#9Oj{zGGd0}UGu1NI=of!(dH|P zUgBlQgI)CIK%ePHg_=8IFE5LY*$$ghxnhp7Tk}=y$bge_#ePAkA^KP+JUR>VGurIV%9TVBFy9kLjmc_vSgw#<+b`io zG+H=fY+4D5<|s?FTpfxOOOE;)HrR;=3JS{3G9GYGE<4p|xjG>G73+X=4cKK5Z2kT9 zyeGoa!*PP5_N9g?zhQ}^EmsH4d&Qcj$hm6U7Jw&q!JUQODama9)va(w?c-fpu&GEI zVWe-`={4cX?}atvPG{+L_$K%r-WxoXv+i-=%qYDaCCENH8EO8>O)3AUn|s@GRexVd zUeDcn96N<k37|&{R8*b1F}%g{=HA~Vy~fT1)@D>2a*lM{skI00V($; z|A6Qfhr$yHLRXi{{)NlXr~|(q6dLII>);>yTLoCwrJZ)9yw7fI{C=Yf`y@UUQbW_} zsaE0S3}xs?O?KkDDKu>WX9Okj=4kNyz$Z-x1`;gYgGbuseYSB`BTM-Rt%12I53(su zEIAHyG0US_5B825|Ine+KYmg8FP0M4%FHpX%(p^5FAHth!<8C|AhQxKOTsb1PTAo_BdTH2NbJjJcvI|M1FZ^+viXmqBm9614cHg_koJ{%o zruO@J#LLsYB8Xcsqs;PbvhEPe&elU(a;}T(R$V*UVdRWJWYc%6dh%d}c86v5rMRL5 z{YL@0Yh-t=qzeqYfam#|fVN|oHT-N`JI`x6f|*X=$jV(-%hk9_)jg#J3u0ccKOB&K zx_}|O;1XZJ0$S-!CAJ{2j$pRa7hd@$VrwfG7pQVAmo%2Y$Fk8QT;Es}UTOX~&{Dn) zo2_AI$u{ploNP4sg^&UZJwM!C)y2ln@NBlK&a8uus^3{1Q-XYO##cp_-sVQ!U!3=< z8iRkOa4ulKVKqxP^R zv0K|S^AfK&c56GiZq2p0d_UFXbcSnJzz-x-%1KxtTFHSfFc3LVb!)ChD7nye1SdIt zHO?B;(R$~>4wbH?Ae0xsFD#UoJQf((w?)Yd$DvMhmYv>Gxb&^? zK9JjQ{ak!QeDKUX_oJ@E*cp`I8P~0q5|NJ%%gB7x)k-!xRIg}zzS%-8p8(5SFI%|$ z8#Q(~R0rcDU<+82k1uz_4KTRcAwgahV#4gaC=mw`_@2x#wYl)}e>PuFv`fo~bk+zrZIqVM3`#7+b5!54!y zoV3u>PN(t&Ik%|hGbm&08jxojPGLZUaJEqTnaAkM$EY+28FpKU;TZFMc?@=pO~6qe z;FvZL62-GSp+}Ee$d4ajCXR`=nNl-CPAkOEDLjU9cOa$fi03=>L6uhRxpjZx1A3Pn z*4Tc20yD6Mrea@147ebP#V4;tXd?9^Yv$WOvW|Gh?Ec-xkF07BXVfRD11x*KeZ(_) zS9yLnIAl>wP%sqIZ6h*ZW}74_KLjN4M+;Z#1Yav>WnNfHpyoo5QZZWN^#iYfzq( zRXFVz+$ckWsz{ckMwY-8b$bgV1XcjYC4-_y3?4Bk+}p_gk8oWBg-5t`$HNf*HFzu> z`?y|HL~S8Ue`-|Y>B;`5s-kPi%Z;=Nle6lYuEsE}4-{uxBDI7Ah|@Jwb7tjtI)MIN zGc~I?d&U{rnaf{a8^vFLZr&c%cAG36^^ZlW4a$GLpEGtzub_9OJ>Dhl@~0N>wOT#k zv*GDB|7g$|X-m3*OPo~1e0oTTkAklYn4obz(39i~suICd2=n|5O>Ipx^=CG^F#jEE zZc~~VhW@_Qu`_$oBC7IuU?9^`8hb^SLPuUE&1R)sruuNxEU8xxOjJH|GkhLq7tH-spRj-e0mrV3mDTkjeRt8U;QmV;}M&xqb4gK78V`TOx&*vb+FB|3uwY&&D?c17^uQ$)kT%|m#sC>I}eRF z@TO4aHE_lw17PEEFyxby3$PDugg4;lp-0xjf8 zyQDwD>eh7+aZYoO1FhU^DV_;_8J%;g!8h%arsAYtQ24=bfO-0Ng$GR1-`&_@fG3Pt z^ARf*vD8YePodQ&N$%U?0r&V`np470v+GV~!R}&vkS}xE{~p8I3k-(-`l496h5@Gu z5d|`&9Yz&b!DR+hVC6M?ofRlMBApctz)6eTFen)*JthF5Nfdvnpa?HTKDr>s#*(Ki zxu^+hvB#eV)YPCfBPf_AiBu1d2ixtlI~|Mk2^V6ZW2)ji+e(306Lc!!6nCM58(Ie3 zjLZ*kwvO7Pr}qU-pu*|BPopV#G#-U+p_wU=`~` zl}V3%2k`FunhUes)EAnrt$68S**JyHMIM&p;0y4h;p^ZJfv<;efNy}Whd%_q4t_Lz z0e)QOjdUpGulsZ#l-k3f`$|3R#ERkAEvZn46!u;psMBngI7GQSsA%fE*9WU2*dFV45J7!~_TM+-Z|%#nKZKm_wq|=);VKSSV?Fh_ipEun=PIs-;A)g7 ztL!1||{)gxG@6GQ!tmJ~E zLk0C8@IQdPOY?Jry4WM@(^Z{qi=tq;Q9qT+--o$PVBPBE#31IOKf?N-dM1@wf=*d7 zB=)aC%A(X}IBto?+5;RN2Gnk2qOO5XB_{S5fxti~p~1@|W*A`s$k1@VeXlji{ms$? zC=X{!#%U4c+ODk=q8g`sFtpgcXdm$Ffm3f7>FI0)>RW28XZKR@YutQCGR^~o&}f;1 zl^f;B!5JRr9IV|YAS>YUgM%T~ziu|w%$dGtafuRik zJJNkVmW?V|_4tz$(jU)&|0{dRs>P3$Jh5!e*ivTYz%^ugCcqis2E!%7ncx<}t%h3z zXG6SkJ9R7*E(Woe;{H**nU3pw;Tt)|9>%rEIBZ%}>^Zn+;huq;3U?3OlWt&Det*%56>FBQC|SH@)vq2e zDO=9+91iQMvgN;iz`@E^t;~S?)f3B?R5+HDu356UZ1pM>eai9`%S#?#au0IM*hM3- zh5CKI-`61EYdqKDo_rndzk(m$A0CE#dM~2?Uf=Hz==WDISyj4X`J_q4!nt#2&z)q< zTefOR$>OJtc(`22M>y+`Vw}6=*JZ2METJ45^9%Ab^73aH5mr{R%(!?}*^^6F-HO_u zm{?M_Y{_Ednia-Uq`GE_agBY+KfSu-$+FTVlZ;7=Z@oV6iPF*~t5-kv#Ij{i8&~yz zmJ+(d>-}HGn3>N6I31iG&Hy(AE*dTl&ZwH7v3SXo8Ee)&J+FcVQT%`PQ`+$3aZJ~n z3EN?C?HNp$1Q$q$JqEa0c$NJKL(X;d-hOk#}s1ASm1`A86_6^wm{ z?;7BrHbR{(~xf%$h7bkzBJwM7|g=p+b%$o627xKo<+dl zmo%E`;h*>{oehBB_UpUZK=>?dDjNj9Z24nsdC78?yc``M1#P9^^^MC9;rI1e8QU8F z$%mi8xBRd-a~pj2+K!k<$^YreqA}zff3@#w9(=as>*I=F{g(}j?~a_O_{fXmv!y>- zC?2ah9P%w|Lq40{?+>x;-bKI0d!HTh?zHcoslGQoKd$}z@iF&Ks?Gd<%hQGTe7Lds zxAmv@PRV}r;J2o(=@X~E*;&v#==WK#{I>Q_x?>BH@>jgGI9c;KRXu*AEQ-e-4*4~w z6u%W%DneO9NOgD8Y)4lR|DEx5;(|MMKu5YA@!JV`iopAqC zO!w83OxO4{?Cinc4}G_n;U>e)f}0Jeu0+3mF7&?Z`H5ZXo5(nhQ}GWrk-$m0WB zn69H1IOcE^KH){Ci|W6o`;1$4b$8mtta0Nr`>PCd0m_-l=G{LlJL}%iFLYBhVL{Gw zcRyM|uQS?zsPK=DUpIPESe^0b;95=z`9J-sjDte!0%EH!<6QLr^cEuReMc$Jo#XSN zveMXGL`^1^dar=Gh{hFHF@3S5-?7RJb(u2c}-gd9713HxjlqoGN^Fx@b!C+b) z_TboC(s-a}H?nubr{_h8bK`!}jSKi~{ex&D!ihecBVg(2zosB1*vP1l-h5wqmO#%8 L)KjsjF!uid*tncw literal 0 HcmV?d00001 diff --git a/boards/ark/pi6x/firmware.prototype b/boards/ark/pi6x/firmware.prototype new file mode 100644 index 000000000000..6c21025a6bc2 --- /dev/null +++ b/boards/ark/pi6x/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 58, + "magic": "ARKPi6XFWv1", + "description": "Firmware for the ARKPi6X board", + "image": "", + "build_time": 0, + "summary": "ARKPi6X", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1835008, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/ark/pi6x/init/rc.board_defaults b/boards/ark/pi6x/init/rc.board_defaults new file mode 100644 index 000000000000..978dcf43d3cd --- /dev/null +++ b/boards/ark/pi6x/init/rc.board_defaults @@ -0,0 +1,33 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# transision from params file to flash-based params (2022-08) +if [ -f $PARAM_FILE ] +then + param load $PARAM_FILE + param save + # create a backup + mv $PARAM_FILE ${PARAM_FILE}.bak + reboot +fi + +param set-default SENS_EN_INA226 1 + +# TODO: Set params to start UXRCE DDS on Telem2 + +# TODO: Start Mavlink on USB by default + +# TODO: Tune the following parameters +param set-default SENS_EN_THERMAL 1 +param set-default SENS_IMU_TEMP 10.0 +#param set-default SENS_IMU_TEMP_FF 0.0 +#param set-default SENS_IMU_TEMP_I 0.025 +#param set-default SENS_IMU_TEMP_P 1.0 + +if ver hwtypecmp ARKPI6X000 +then + # TODO: Add the correct sensor ID + param set-default SENS_TEMP_ID 2490378 +fi diff --git a/boards/ark/pi6x/init/rc.board_sensors b/boards/ark/pi6x/init/rc.board_sensors new file mode 100644 index 000000000000..647e685c7f43 --- /dev/null +++ b/boards/ark/pi6x/init/rc.board_sensors @@ -0,0 +1,34 @@ +#!/bin/sh +# +# ARKPI6X specific board sensors init +#------------------------------------------------------------------------------ + +board_adc start + +if param compare SENS_EN_INA226 1 +then + # Start Digital power monitors + ina226 -I -b 3 -t 1 -k start +fi + +if ver hwtypecmp ARKPI6X000 +then + # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz + icm42688p -R 3 -s -b 1 -C 32051 start + + # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz + icm42688p -R 1 -s -b 2 -C 32051 start +fi + +# Internal magnetometer on I2C +# TODO: Write a driver for the MMC5983MA +mmc5983ma -I -b 4 start + +# Internal Baro on I2C +bmp388 -I -b 4 start + +# Internal optical flow +paw3902 -s -b 3 start -Y 90 + +# Internal distance sensor +afbrs50 start diff --git a/boards/ark/pi6x/nuttx-config/Kconfig b/boards/ark/pi6x/nuttx-config/Kconfig new file mode 100644 index 000000000000..bb33d3cfda4d --- /dev/null +++ b/boards/ark/pi6x/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/ark/pi6x/nuttx-config/bootloader/defconfig b/boards/ark/pi6x/nuttx-config/bootloader/defconfig new file mode 100644 index 000000000000..745251793bd0 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/bootloader/defconfig @@ -0,0 +1,95 @@ +# +# 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_DISABLE_PTHREAD 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/ark/pi6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="ark" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0039 +CONFIG_CDCACM_PRODUCTSTR="ARK BL Pi6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ARK" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART7=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_UART7_RXBUFSIZE=512 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=512 +CONFIG_UART7_TXDMA=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/pi6x/nuttx-config/include/board.h b/boards/ark/pi6x/nuttx-config/include/board.h new file mode 100644 index 000000000000..2b716936cebd --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/include/board.h @@ -0,0 +1,512 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6x/include/board.h + * + * Copyright (C) 2016-2024 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_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_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 px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The ARKV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#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_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS No remap /* PC8 */ +#define GPIO_UART5_CTS (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9|GPIO_PULLDOWN) /* PC9 */ + +#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_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + + +/* 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 sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is Not Used + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* 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_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_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_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_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/ark/pi6x/nuttx-config/include/board_dma_map.h b/boards/ark/pi6x/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..62e278597243 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/include/board_dma_map.h @@ -0,0 +1,81 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/ark/pi6x/nuttx-config/nsh/defconfig b/boards/ark/pi6x/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..947fee32b15f --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/nsh/defconfig @@ -0,0 +1,274 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/pi6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="ark" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0039 +CONFIG_CDCACM_PRODUCTSTR="ARK Pi6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ARK" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=3000 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_USART1=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_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld b/boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..b0515c91c7f8 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2024 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 ARKV6X 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 ARKV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/pi6x/nuttx-config/scripts/script.ld b/boards/ark/pi6x/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..8e6dca3e4941 --- /dev/null +++ b/boards/ark/pi6x/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2024 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 ARKV6X 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 ARKV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */ + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/pi6x/src/CMakeLists.txt b/boards/ark/pi6x/src/CMakeLists.txt new file mode 100644 index 000000000000..78b8222f19d8 --- /dev/null +++ b/boards/ark/pi6x/src/CMakeLists.txt @@ -0,0 +1,77 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + mtd.cpp + sdio.c + spi.cpp + spix_sync.c + spix_sync.h + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/ark/pi6x/src/board_config.h b/boards/ark/pi6x/src/board_config.h new file mode 100644 index 000000000000..5e123db35124 --- /dev/null +++ b/boards/ark/pi6x/src/board_config.h @@ -0,0 +1,402 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2024 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 + * + * ARK Pi6X internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_NBAT_V 1d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 1d // 2 Digital Current + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define PX4_I2C_OBDEV_SE050 0x48 + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15) + +#define ADC_CHANNELS \ + ((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL)) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ +#define BOARD_HAS_HW_SPLIT_VERSIONING + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 +#define HW_INFO_INIT_PREFIX "ARKPI6X" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 +// Base/FMUM +#define ARKPI6X_0 HW_FMUM_ID(0x0) // ARKPI6X, Sensor Set Rev 0 +#define ARKPI6X_1 HW_FMUM_ID(0x1) // ARKPI6X, Sensor Set Rev 1 + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PE6 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +#define GPIO_FMU_CH1 /* PI0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN0) +#define GPIO_FMU_CH2 /* PH12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN12) +#define GPIO_FMU_CH3 /* PH11 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN11) +#define GPIO_FMU_CH4 /* PH10 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN10) +#define GPIO_FMU_CH5 /* PD13 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTD|GPIO_PIN13) +#define GPIO_FMU_CH6 /* PD14 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTD|GPIO_PIN14) +#define GPIO_FMU_CH7 /* PH6 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN6) +#define GPIO_FMU_CH8 /* PH9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN9) + +#define GPIO_FMU_CAP /* PE11 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN11) +#define GPIO_SPIX_SYNC /* PE9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN9) + +#define BROADCOM_AFBR_S50_S2PI_SPI_BUS 6 +#define BROADCOM_AFBR_S50_S2PI_CS /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10) +#define BROADCOM_AFBR_S50_S2PI_IRQ /* PD11 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN11|GPIO_EXTI) +#define BROADCOM_AFBR_S50_S2PI_CLK /* PB3 */ GPIO_SPI6_SCK_3 +#define BROADCOM_AFBR_S50_S2PI_MOSI /* PG14 */ GPIO_SPI6_MOSI_1 +#define BROADCOM_AFBR_S50_S2PI_MISO /* PA6 */ GPIO_SPI6_MISO_2 + +/* Power supply control and monitoring GPIOs */ + +#define BOARD_NUMBER_BRICKS 0 +#define BOARD_NUMBER_DIGITAL_BRICKS 1 + +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* Spare GPIO */ + +#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +#define FLASH_BASED_PARAMS + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +/* RC Serial port */ + +#define RC_SERIAL_PORT "/dev/ttyS4" + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) + +/* ARKPI6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_PD15, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nARMED_INIT, \ + GPIO_FMU_CH1, \ + GPIO_FMU_CH2, \ + GPIO_FMU_CH3, \ + GPIO_FMU_CH4, \ + GPIO_FMU_CH5, \ + GPIO_FMU_CH6, \ + GPIO_FMU_CH7, \ + GPIO_FMU_CH8, \ + GPIO_FMU_CAP, \ + GPIO_SPIX_SYNC \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 3 +#define BOARD_SPIX_SYNC_FREQ 32000 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/ark/pi6x/src/bootloader_main.c b/boards/ark/pi6x/src/bootloader_main.c new file mode 100644 index 000000000000..7a3ef5e01932 --- /dev/null +++ b/boards/ark/pi6x/src/bootloader_main.c @@ -0,0 +1,85 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file 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 +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure pins */ + const uint32_t list[] = PX4_GPIO_INIT_LIST; + + for (size_t gpio = 0; gpio < arraySize(list); gpio++) { + if (list[gpio] != 0) { + px4_arch_configgpio(list[gpio]); + } + } + + /* 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/ark/pi6x/src/can.c b/boards/ark/pi6x/src/can.c new file mode 100644 index 000000000000..cdebe7a3ad61 --- /dev/null +++ b/boards/ark/pi6x/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/ark/pi6x/src/hw_config.h b/boards/ark/pi6x/src/hw_config.h new file mode 100644 index 000000000000..52c70ec748da --- /dev/null +++ b/boards/ark/pi6x/src/hw_config.h @@ -0,0 +1,129 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS5,921600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 58 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/ark/pi6x/src/i2c.cpp b/boards/ark/pi6x/src/i2c.cpp new file mode 100644 index 000000000000..86c060404934 --- /dev/null +++ b/boards/ark/pi6x/src/i2c.cpp @@ -0,0 +1,40 @@ +/**************************************************************************** + * + * Copyright (C) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusInternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/ark/pi6x/src/init.c b/boards/ark/pi6x/src/init.c new file mode 100644 index 000000000000..90bb4fc128be --- /dev/null +++ b/boards/ark/pi6x/src/init.c @@ -0,0 +1,293 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * ARKFMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" +#include "spix_sync.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_HIPOWER_EN(false); + board_control_spi_sensors_power(false, 0xffff); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_HIPOWER_EN(true); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(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) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Power on Interfaces */ + VDD_5V_HIPOWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {15, 128 * 1024, 0x081E0000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + led_on(LED_AMBER); + } + +#endif // FLASH_BASED_PARAMS + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +#if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +#endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +#endif /* CONFIG_MMCSD */ + + /* Configure the SPIX_SYNC output */ + spix_sync_servo_init(BOARD_SPIX_SYNC_FREQ); + spix_sync_servo_set(0, 150); + + return OK; +} diff --git a/boards/ark/pi6x/src/led.c b/boards/ark/pi6x/src/led.c new file mode 100644 index 000000000000..b629ade32c36 --- /dev/null +++ b/boards/ark/pi6x/src/led.c @@ -0,0 +1,234 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * ARKFMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/ark/pi6x/src/mtd.cpp b/boards/ark/pi6x/src/mtd.cpp new file mode 100644 index 000000000000..bd74d551ee4c --- /dev/null +++ b/boards/ark/pi6x/src/mtd.cpp @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * Copyright (C) 2024 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 +#include + +static const px4_mft_entry_s mft_mft = { + .type = MFT, + .pmft = (void *) system_query_manifest, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mft_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/ark/pi6x/src/sdio.c b/boards/ark/pi6x/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/ark/pi6x/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/ark/pi6x/src/spi.cpp b/boards/ark/pi6x/src/spi.cpp new file mode 100644 index 000000000000..bae9af7622a3 --- /dev/null +++ b/boards/ark/pi6x/src/spi.cpp @@ -0,0 +1,83 @@ +/**************************************************************************** + * + * Copyright (C) 2024 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_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { + initSPIFmumID(ARKPI6X_0, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_FLOW_DEVTYPE_PAW3902, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + // initSPIBus(SPI::Bus::SPI5, { + // initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + // }), + initSPIBus(SPI::Bus::SPI6, { + initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}) + }), + }), + initSPIFmumID(ARKPI6X_1, { // Placeholder + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_FLOW_DEVTYPE_PAW3902, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + // initSPIBus(SPI::Bus::SPI5, { + // initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + // }), + initSPIBus(SPI::Bus::SPI6, { + initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}) + }), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); diff --git a/boards/ark/pi6x/src/spix_sync.c b/boards/ark/pi6x/src/spix_sync.c new file mode 100644 index 000000000000..056e38e75f74 --- /dev/null +++ b/boards/ark/pi6x/src/spix_sync.c @@ -0,0 +1,309 @@ +/**************************************************************************** + * + * Copyright (C) 2023 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 Airmind 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 spix_sync.c +* +* +*/ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +#include +#include +#include + +#include + +#include "spix_sync.h" + +#define REG(_tmr, _reg) (*(volatile uint32_t *)(spix_sync_timers[_tmr].base + _reg)) + +#define rCR1(_tmr) REG(_tmr, STM32_GTIM_CR1_OFFSET) +#define rCR2(_tmr) REG(_tmr, STM32_GTIM_CR2_OFFSET) +#define rSMCR(_tmr) REG(_tmr, STM32_GTIM_SMCR_OFFSET) +#define rDIER(_tmr) REG(_tmr, STM32_GTIM_DIER_OFFSET) +#define rSR(_tmr) REG(_tmr, STM32_GTIM_SR_OFFSET) +#define rEGR(_tmr) REG(_tmr, STM32_GTIM_EGR_OFFSET) +#define rCCMR1(_tmr) REG(_tmr, STM32_GTIM_CCMR1_OFFSET) +#define rCCMR2(_tmr) REG(_tmr, STM32_GTIM_CCMR2_OFFSET) +#define rCCER(_tmr) REG(_tmr, STM32_GTIM_CCER_OFFSET) +#define rCNT(_tmr) REG(_tmr, STM32_GTIM_CNT_OFFSET) +#define rPSC(_tmr) REG(_tmr, STM32_GTIM_PSC_OFFSET) +#define rARR(_tmr) REG(_tmr, STM32_GTIM_ARR_OFFSET) +#define rCCR1(_tmr) REG(_tmr, STM32_GTIM_CCR1_OFFSET) +#define rCCR2(_tmr) REG(_tmr, STM32_GTIM_CCR2_OFFSET) +#define rCCR3(_tmr) REG(_tmr, STM32_GTIM_CCR3_OFFSET) +#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET) +#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET) +#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET) +#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET) + +#define BOARD_SPIX_SYNC_PWM_FREQ 1024000 + +unsigned +spix_sync_timer_get_period(unsigned timer) +{ + return (rARR(timer)); +} + +static void spix_sync_timer_init_timer(unsigned timer, unsigned rate) +{ + if (spix_sync_timers[timer].base) { + + irqstate_t flags = px4_enter_critical_section(); + + /* enable the timer clock before we try to talk to it */ + + modifyreg32(spix_sync_timers[timer].clock_register, 0, spix_sync_timers[timer].clock_bit); + + /* disable and configure the timer */ + rCR1(timer) = 0; + rCR2(timer) = 0; + rSMCR(timer) = 0; + rDIER(timer) = 0; + rCCER(timer) = 0; + rCCMR1(timer) = 0; + rCCMR2(timer) = 0; + rCCR1(timer) = 0; + rCCR2(timer) = 0; + rCCR3(timer) = 0; + rCCR4(timer) = 0; + rCCER(timer) = 0; + rDCR(timer) = 0; + + if ((spix_sync_timers[timer].base == STM32_TIM1_BASE) || (spix_sync_timers[timer].base == STM32_TIM8_BASE)) { + + /* master output enable = on */ + + rBDTR(timer) = ATIM_BDTR_MOE; + } + + /* If the timer clock source provided as clock_freq is the STM32_APBx_TIMx_CLKIN + * then configure the timer to free-run at 1MHz. + * Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly. + */ + + rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_SPIX_SYNC_PWM_FREQ) - 1; + + /* configure the timer to update at the desired rate */ + + rARR(timer) = (BOARD_SPIX_SYNC_PWM_FREQ / rate) - 1; + + /* generate an update event; reloads the counter and all registers */ + rEGR(timer) = GTIM_EGR_UG; + + px4_leave_critical_section(flags); + } + +} + +void spix_sync_channel_init(unsigned channel) +{ + /* Only initialize used channels */ + + if (spix_sync_channels[channel].timer_channel) { + + unsigned timer = spix_sync_channels[channel].timer_index; + + /* configure the GPIO first */ + px4_arch_configgpio(spix_sync_channels[channel].gpio_out); + + uint16_t polarity = spix_sync_channels[channel].masks; + + /* configure the channel */ + switch (spix_sync_channels[channel].timer_channel) { + case 1: + rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC1M_SHIFT) | GTIM_CCMR1_OC1PE; + rCCER(timer) |= polarity | GTIM_CCER_CC1E; + break; + + case 2: + rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC2M_SHIFT) | GTIM_CCMR1_OC2PE; + rCCER(timer) |= polarity | GTIM_CCER_CC2E; + break; + + case 3: + rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC3M_SHIFT) | GTIM_CCMR2_OC3PE; + rCCER(timer) |= polarity | GTIM_CCER_CC3E; + break; + + case 4: + rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC4M_SHIFT) | GTIM_CCMR2_OC4PE; + rCCER(timer) |= polarity | GTIM_CCER_CC4E; + break; + } + } +} + +int +spix_sync_servo_set(unsigned channel, uint8_t cvalue) +{ + if (channel >= arraySize(spix_sync_channels)) { + return -1; + } + + unsigned timer = spix_sync_channels[channel].timer_index; + + /* test timer for validity */ + if ((spix_sync_timers[timer].base == 0) || + (spix_sync_channels[channel].gpio_out == 0)) { + return -1; + } + + unsigned period = spix_sync_timer_get_period(timer); + + unsigned value = (unsigned)cvalue * period / 255; + + /* configure the channel */ + if (value > 0) { + value--; + } + + + switch (spix_sync_channels[channel].timer_channel) { + case 1: + rCCR1(timer) = value; + break; + + case 2: + rCCR2(timer) = value; + break; + + case 3: + rCCR3(timer) = value; + break; + + case 4: + rCCR4(timer) = value; + break; + + default: + return -1; + } + + return 0; +} + +unsigned spix_sync_servo_get(unsigned channel) +{ + if (channel >= 3) { + return 0; + } + + unsigned timer = spix_sync_channels[channel].timer_index; + uint16_t value = 0; + + /* test timer for validity */ + if ((spix_sync_timers[timer].base == 0) || + (spix_sync_channels[channel].timer_channel == 0)) { + return 0; + } + + /* configure the channel */ + switch (spix_sync_channels[channel].timer_channel) { + case 1: + value = rCCR1(timer); + break; + + case 2: + value = rCCR2(timer); + break; + + case 3: + value = rCCR3(timer); + break; + + case 4: + value = rCCR4(timer); + break; + } + + unsigned period = spix_sync_timer_get_period(timer); + return ((value + 1) * 255 / period); +} + +int spix_sync_servo_init(unsigned rate) +{ + /* do basic timer initialisation first */ + for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) { + spix_sync_timer_init_timer(i, rate); + } + + /* now init channels */ + for (unsigned i = 0; i < arraySize(spix_sync_channels); i++) { + spix_sync_channel_init(i); + } + + spix_sync_servo_arm(true); + return OK; +} + +void +spix_sync_servo_deinit(void) +{ + /* disable the timers */ + spix_sync_servo_arm(false); +} +void +spix_sync_servo_arm(bool armed) +{ + /* iterate timers and arm/disarm appropriately */ + for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) { + if (spix_sync_timers[i].base != 0) { + if (armed) { + /* force an update to preload all registers */ + rEGR(i) = GTIM_EGR_UG; + + /* arm requires the timer be enabled */ + rCR1(i) |= GTIM_CR1_CEN | GTIM_CR1_ARPE; + + } else { + rCR1(i) = 0; + } + } + } +} diff --git a/boards/ark/pi6x/src/spix_sync.h b/boards/ark/pi6x/src/spix_sync.h new file mode 100644 index 000000000000..2e37c8908613 --- /dev/null +++ b/boards/ark/pi6x/src/spix_sync.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * Copyright (C) 2023 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. + * + ****************************************************************************/ + +__BEGIN_DECLS +void spix_sync_channel_init(unsigned channel); +int spix_sync_servo_set(unsigned channel, uint8_t value); +unsigned spix_sync_servo_get(unsigned channel); +int spix_sync_servo_init(unsigned rate); +void spix_sync_servo_deinit(void); +void spix_sync_servo_arm(bool armed); +unsigned spix_sync_timer_get_period(unsigned timer); +__END_DECLS diff --git a/boards/ark/pi6x/src/timer_config.cpp b/boards/ark/pi6x/src/timer_config.cpp new file mode 100644 index 000000000000..bee77b999337 --- /dev/null +++ b/boards/ark/pi6x/src/timer_config.cpp @@ -0,0 +1,88 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + //initIOTimer(Timer::Timer1), + //initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + 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::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + //initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + //initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); + + +constexpr io_timers_t spix_sync_timers[MAX_SPIX_SYNC_TIMERS] = { + initIOTimer(Timer::Timer1), +}; + +constexpr timer_io_channels_t spix_sync_channels[MAX_SPIX_SYNC_TIMERS] = { + initIOTimerChannel(spix_sync_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), +}; diff --git a/boards/ark/pi6x/src/usb.c b/boards/ark/pi6x/src/usb.c new file mode 100644 index 000000000000..1c64e94ba104 --- /dev/null +++ b/boards/ark/pi6x/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include "arm_internal.h" +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the ARKFMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp index 4df96fa5a996..5310701eebda 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp @@ -72,7 +72,7 @@ static constexpr wq_config_t INS1{"wq:INS1", 6000, -15}; static constexpr wq_config_t INS2{"wq:INS2", 6000, -16}; static constexpr wq_config_t INS3{"wq:INS3", 6000, -17}; -static constexpr wq_config_t hp_default{"wq:hp_default", 2392, -18}; +static constexpr wq_config_t hp_default{"wq:hp_default", 2800, -18}; static constexpr wq_config_t uavcan{"wq:uavcan", 3624, -19}; diff --git a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c index 894834f078fa..859d861b2094 100644 --- a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c +++ b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c @@ -71,6 +71,14 @@ const mcu_rev_t silicon_revs[] = { {MCU_REV_Z, 'Z'}, /* Revision Z */ }; +/* + * If APP_RESERVATION_SIZE is greater than 0 and + * FLASH_BASED_PARAMS is defined, throw a compile error + */ +#if defined(FLASH_BASED_PARAMS) && (APP_RESERVATION_SIZE <= 0) +# error "APP_RESERVATION_SIZE must be greater than 0 if FLASH_BASED_PARAMS is defined" +#endif + #define APP_SIZE_MAX (BOARD_FLASH_SIZE - (BOOTLOADER_RESERVATION_SIZE + APP_RESERVATION_SIZE)) diff --git a/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c b/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c index 015249f859f5..367c5417df60 100644 --- a/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c +++ b/src/drivers/distance_sensor/broadcom/afbrs50/API/Src/s2pi.c @@ -362,9 +362,9 @@ status_t S2PI_TransferFrame(s2pi_slave_t spi_slave, uint8_t const *txData, uint8 } /* Check the spi slave.*/ - if (spi_slave != S2PI_S2) { - return ERROR_S2PI_INVALID_SLAVE; - } + // if (spi_slave != S2PI_S2) { + // return ERROR_S2PI_INVALID_SLAVE; + // } /* Check the driver status, lock if idle. */ IRQ_LOCK();