From 37475d2557e1b59b64151f79cd683497dc213618 Mon Sep 17 00:00:00 2001 From: czx-fly <134139706+czx-fly@users.noreply.github.com> Date: Sat, 9 Aug 2025 11:38:53 +0800 Subject: [PATCH] boards: new xc-fly xc-slam board support (#25364) --- boards/xc-fly/xc-slam/bootloader.px4board | 3 + boards/xc-fly/xc-slam/default.px4board | 90 ++++ .../extras/xc-fly_xc-slam_bootloader.bin | Bin 0 -> 43280 bytes boards/xc-fly/xc-slam/firmware.prototype | 13 + boards/xc-fly/xc-slam/init/rc.board_defaults | 26 + boards/xc-fly/xc-slam/init/rc.board_extras | 7 + boards/xc-fly/xc-slam/init/rc.board_sensors | 20 + boards/xc-fly/xc-slam/nuttx-config/Kconfig | 17 + .../xc-slam/nuttx-config/bootloader/defconfig | 90 ++++ .../xc-slam/nuttx-config/include/board.h | 491 +++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 62 +++ .../xc-fly/xc-slam/nuttx-config/nsh/defconfig | 268 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 ++++++++ .../xc-slam/nuttx-config/scripts/script.ld | 228 ++++++++ boards/xc-fly/xc-slam/src/CMakeLists.txt | 69 +++ boards/xc-fly/xc-slam/src/board_config.h | 234 ++++++++ boards/xc-fly/xc-slam/src/bootloader_main.c | 75 +++ boards/xc-fly/xc-slam/src/flash_w25q128.c | 505 ++++++++++++++++++ boards/xc-fly/xc-slam/src/hw_config.h | 135 +++++ boards/xc-fly/xc-slam/src/i2c.cpp | 39 ++ boards/xc-fly/xc-slam/src/init.c | 210 ++++++++ boards/xc-fly/xc-slam/src/led.c | 113 ++++ boards/xc-fly/xc-slam/src/manifest.c | 131 +++++ boards/xc-fly/xc-slam/src/mtd.cpp | 78 +++ boards/xc-fly/xc-slam/src/sdio.c | 177 ++++++ boards/xc-fly/xc-slam/src/spi.cpp | 55 ++ boards/xc-fly/xc-slam/src/timer_config.cpp | 61 +++ boards/xc-fly/xc-slam/src/usb.c | 78 +++ 28 files changed, 3488 insertions(+) create mode 100644 boards/xc-fly/xc-slam/bootloader.px4board create mode 100644 boards/xc-fly/xc-slam/default.px4board create mode 100755 boards/xc-fly/xc-slam/extras/xc-fly_xc-slam_bootloader.bin create mode 100644 boards/xc-fly/xc-slam/firmware.prototype create mode 100644 boards/xc-fly/xc-slam/init/rc.board_defaults create mode 100644 boards/xc-fly/xc-slam/init/rc.board_extras create mode 100644 boards/xc-fly/xc-slam/init/rc.board_sensors create mode 100644 boards/xc-fly/xc-slam/nuttx-config/Kconfig create mode 100644 boards/xc-fly/xc-slam/nuttx-config/bootloader/defconfig create mode 100644 boards/xc-fly/xc-slam/nuttx-config/include/board.h create mode 100644 boards/xc-fly/xc-slam/nuttx-config/include/board_dma_map.h create mode 100644 boards/xc-fly/xc-slam/nuttx-config/nsh/defconfig create mode 100644 boards/xc-fly/xc-slam/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/xc-fly/xc-slam/nuttx-config/scripts/script.ld create mode 100644 boards/xc-fly/xc-slam/src/CMakeLists.txt create mode 100644 boards/xc-fly/xc-slam/src/board_config.h create mode 100644 boards/xc-fly/xc-slam/src/bootloader_main.c create mode 100644 boards/xc-fly/xc-slam/src/flash_w25q128.c create mode 100644 boards/xc-fly/xc-slam/src/hw_config.h create mode 100644 boards/xc-fly/xc-slam/src/i2c.cpp create mode 100644 boards/xc-fly/xc-slam/src/init.c create mode 100644 boards/xc-fly/xc-slam/src/led.c create mode 100644 boards/xc-fly/xc-slam/src/manifest.c create mode 100644 boards/xc-fly/xc-slam/src/mtd.cpp create mode 100644 boards/xc-fly/xc-slam/src/sdio.c create mode 100644 boards/xc-fly/xc-slam/src/spi.cpp create mode 100644 boards/xc-fly/xc-slam/src/timer_config.cpp create mode 100644 boards/xc-fly/xc-slam/src/usb.c diff --git a/boards/xc-fly/xc-slam/bootloader.px4board b/boards/xc-fly/xc-slam/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/xc-fly/xc-slam/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/xc-fly/xc-slam/default.px4board b/boards/xc-fly/xc-slam/default.px4board new file mode 100644 index 0000000000..7a7cb9d880 --- /dev/null +++ b/boards/xc-fly/xc-slam/default.px4board @@ -0,0 +1,90 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS7" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS2" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DISTANCE_SENSOR_TF02PRO=y +CONFIG_DRIVERS_DISTANCE_SENSOR_TFMINI=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y +CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_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_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y +CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/xc-fly/xc-slam/extras/xc-fly_xc-slam_bootloader.bin b/boards/xc-fly/xc-slam/extras/xc-fly_xc-slam_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..b8f290f227d59ed1017ceb014a84b370bbd53dc4 GIT binary patch literal 43280 zcmeFZdwf*Yxi`M{WoC9RkO>Jgxd3wsm}G(s1T=`&VJ7Tc22B91T&xZRJv+og1gxkO zCImHzwn(rA(pDteQc=kSriXwrQP66w=ga`<2}ElIWkZ6xhXiKlI=}ClA+}ZfzQ6as z_m6izpFL~sy`Q}<&wAFgp4(c}4J1Ru5#f*Q|GWMl4*u_<0doBpzWnZvpZr|&-ZwoO z&jf`}VEy0p#8f>mt`ymz#D3G0SUo|}C&af*`AYxn_J%2!220At&(usmQ6B1VxHwo6 zecNzZ|E%3czmIS6^awSco|u~Ip2V8U0)ZzPf^ULrLgCr;cP5NUH7gvu+fma(%)~^L z-wvj@Qor}+h9aUoIY5+zKBBn#iBjIz(o^!wmY&tWEKxcwr_}9J%?iUFM|w)#c|E^# z>Ie)`jt&xq!*?GJl9v3jsGlJjJT7!OBYr;-Ru*q=IH{5umR^s=+3U%D7x{-=Of6GK ztfZ&eLsNUte|p@mQ>r1u+*`TatR%1wML?Z~j8kelo^>vFD0bYZ|Kq;bvpjl_ZF z)AtnK_)qu7j5~{utC<<|@NbL!=Vh>0$@Jr@J);QEasW><9LoL$$C1+fc4nZBrin;z zLyJhp4nm*AXF3!uYKYH7D>EIvb_Z&Ud0+4kjj>MFO~0`4(2i_J9P zUpPibp4q|FZF8`n?!Ed%V=Y5QxB}%I#0)wF&q$sEngdNHPZ@bzS#XOl_Re_GD#bOWi&<`FJ5jEx zSrW60C^ZAgO~jHTS=~mFYp`J~<0H6Bu68OsSKX6b6Xi-Xz=`M_oPio@P(vl=P|XxN z&Iy@%-?UHn2KD^JoY+sepxen^UFM8)GZwC&?@e|SV|wQuIYN8-JX>CRethIPQS|OB z@&h@1yJ22wMoRE1wpmWjMK`$-*=cH4>6^~1gE8{Dqop|P>y)qWj8kS0&lE5uV z=Yn~bWw~`^j>^Yva|{G1grNxYZG4I1nFj7N9{dlNar{CisW{rt6;6lBr_};l?;>V> zQJgW=O_V?N6Z7aI&PWt*KT0v5RMT&_D4U#4rPKK?@`{Dh&hkGA%^tJ~d|M!2ppC%$ znHa30xRQJx3-emJ$cy1nN!Zwwkn`y!GL8K-#mzS8n^Pro7sIByRXNE=zJ;6p18}j< zRCk|@bt=-|Q)$J&p7w&7I#sWY3;jL9LI*o5Si36@OK zaJ6k>=<`+_`sR37Qy|7tY&?C`bq2kG~8+|X9bNIB7QZ!HFjGJiM!`oEqSF8B0g~lG$}6KDCETRD|UW3uzkD84ye%%tDx-e|P?*;_3t zyOhf|oViaow@V}5(2_hcS#+v=g<0gf`FLG+Qu{e!wW8DM23W^!b}rkJzomu0l|nGt z?3w8ItT&}nX@0$%)d{!$`4V~Pyv$|)tzD6s><M82G* zY9r}El~JY+4$8UGQqqX|Z@~ONj7tIENE}53J@O}T{S{XOu2x*HIAggc%hLLi;; zH}H(m;;_bLzxISs6faP1wxwRSyOmua?JCf^QYBn&p_!O9u4{6tNWY=*BYmac3si3S z0p5BucxyORGkh=Ft8t}CRXryywa{`XFHLgkeW}vB-Z6kX&_v~s z@Ajy%&uAmom`{i$X-h1i7B)rYC1TV!GqdX&leQ4+)xbA0qxkxR@<_QyPv7~_7KMwO4!-+oKZ`hsM-+X+D%t#Vr zMb;D!wMO0~`S|Nki8&nV4$~2za;c}_=}k4FMtnh>CQcMTRWtVz&>}zK)(+IGa9X0Y z<1W7A8SesdmY9h-=WakJV!-~2C`l?m;ao@jo;i3+l)bp?h?MyAK1zw;hR=|eQAtFYaw$~8i=#zm z$8HfL^33;F&(GAsy|_GQRZ>cf?JBV`GxLfQr5eYm4!zWhS(~EHDAtH1b8aBq_zY+d z_#?AAnJJ0VkrrkWGb_u!P&GAh-BqKH1xdoxz<;U49&Y^7{TGx-;hDN?jlWfG#>FCM zoV<>%IuES_Cz*AAn?)((lAL@npFLj<-ifwvQPUe3<^KL~=!4;L;4qwW09?fKSUBV# zUIaN0J^Ljyld-)iCrTv>i67-EB8l!)3GF6q_sKPHbuUlgJ6Ppl_yg3wQ!Z6=NPLiq zPnF)0m|J7*b5%2uLH~4qzk-X-Z#vIsxG1JbR&vW$akr=wNyb>QNHmx$Z5()dq4L_k*^VkTy!;MI8VKW{hZ6Vu!RuTA&(juBP+b zUM-Kp2!TX#e?d6(^dMuaaeNbCjH=9l5;^57RgKJBUW5kW`=XI^nM4ET-GKokDF0U~ zozr@s!NlY48`bEompUX4lC~b)EDqeP(g%F@{-Tmq{yxl$+rjG(4QM9tn8~d2-f*T^ z*~|ws$YHlu`KTZ5oWv>b^z}q$v?BX2vC~uCjCskL%7Q%K7D*${@RmKnSot%|?6Nh) za=@JjEq#2n$No7en_>V=!3 zm9jS_`nj8u{mf0tft3%Nq*y1(Sh=Djq8Sn;5n6QakWo~dP14GTsr3DgY?i(P#>VoO zF%Rf?7+f~rcas>LuUYToo~(|pFW;f+(M7Cs zS9pZ3S!;X%_5FY*uPN%18S7Vp=8JketLz5u^J1YpYbm=l6V z6`nzBrlU@R^ECABt>MxpK6rN|KO>yi1eob3E+x{DRNfqftf(9qROILv`UsRMoY`bR zIjoW%HZ)PV%>!5DaOl_JUKw)ooKa%TdS1*rly75|SHeuDPTWY_PbGuz^wYBGTBFuF zCXltB4;B)N9kC@poiu$#%36=ID5X-|!>U1XPpumD z8PLmY*$5^Kay!RBc$~(ixrn`|g50lK3eyikk zS4h?F$cTQgg*-;_t43CNW|)rJG5Lr4VTWA9DlZO4TAJAw&>LCh>>$ak_d^F?`!R6y z-ayv+z2F~z9?)V1%JJK!!b3zkIY2U9{B6b zrz&tV?f=M@O&Ti~;2}p7WlXcR1AZ_G*PCk-GuVNXat|Jm}}-5Qo*z6NA3QGPR&W;c%bX#@3?!)!a)M z-)GkRX)9Xx4954|HtyG-HI9KbFxF33V^%pd#ME(awytc8F0!7Mikcm?OwAsO-=eF5IGip6oz5L;O?3=sd*s=Dfy5djEL=FQtqyd>7z3=96EWF@+rZ`x)@^`-WK;o?>&+cb7eH>@pKC;j?nUnMJOHvj$H*# z!ge3$7Oih}5`}?|!{o+UgIK953)W*@%=0}ZErHE0l|qv$M@j@*6Eu?hq_-lx<@~mSUJF z`;So0mxuXhhQtDH4nF{^Bn}bdWvrUfwOQ{w0UiUX_4-$=GI%t@MwADS5{u5qip+M# zWPr^3(EziDShOa_s8!w@fSqTL*2E&;GC+(`N)BJ z4)X5kTA^=7i+;e0%YiFs1I)v5HB4?=W1NRrxD`>!fXXcRW(#maWeLnC$~hw|{3cCy zOhEH+b`3LqOk=i(nCEO^!Qt0lZ(APpc@=tTrYq|%xAFKTlAr0K|2JO$e;;{z&nh|n z8nMtzf^J>TqnV;%<}}dNp9T&(LIF2MetbVKE~0NW?2Y5@y75t?XqZ7EULAN95OzSs zUx%=3$c_5DZd_{=^%01j-$D%ZMa!_G4B?+3sv{6;vjJ-?>?awSbgjij*W7=HeXfYk zwuc7jY@@n0{gz7UW5v?qiC7)sm1r0(cBsN${tO+Bs3bk7X_iKWh;GG#clC;Vrbn4>WNHT0EynsSnA zaOyZxOXwPoQQdZZRE=0k4FjZ(7o(i8)Jsd!K|lJc|3UX!sos4^I`4i-E(P98`;v=z zu{9zAqLi)CQnrHAl3*!o6q9E_TeYx?zn|=hE!yc|>UsmwQfd8!a_5@pH#Nu!;yV!; zo#K;NZt-oF7`k#i^<8a!XL(Ljbfz%7sD<71IJ2KsW({OWS0LAnf{oYi9S-$|Gs=^_ zmJJ6STwpjf1c^4UIYYWChcAx-FHe)4-bD1YzQ40cUl^6QetR@R=iieVbcJ-hf6-6J z82@EK-_xkMyz>o4?1s$QujU^VWW1bh}5mi$P42F3CK4pV5DXO57v}i7NbeJMf<8 zix+h+jkr*qrsuj(aA}Ws=(sklgKExWdCjacslQ(ygk4JGVmIl13)Sg*y6)Th33OpP z7w9{^FHT}N9P*}b*y+%oTp}%RYQ03JFLDd+q|P*q5xvv93!z=bcSiGzV0kZ=NOmxQ z``mXf5yC+8qU-K0zA<;^NI8+QTHVipPurRk(DL$r=zvM(V#&4m$~RyecwS}g%!{1z zhhYX5rn0xy#$XcWev1XrxtY3)!`LQUA(zQ^%(M@h5%3nRC*N*ivK{#}kOoa!-bLgra=|QBPsdnWJPiqf>E$96(13TLf zNy2QFUHOeCxwo?9L=R^h=eOuel!O>p3v_zUDV8W1@g<5ezK-0dYCB{4xjxd*_1x4I zGuqiTnwzI;Z6#fWF`VUZD(U31xc(Tt<3_LU;^GwsINYeDjTxE`s%A@()o=+$KG=}YDe)X;VDc{eOLkKiVG^7tRAF6IOCUx_AkVO-#WH8Q zSI!dek%@7mOf0)(#_}tfo%F8EO=^`bU4;AZ2<20o3mwDO#&9UDC44zL?)u2M3v}FV z3%#l3(UGU)u6HE27{rKu5o>MqTfxUGX#>2Hf@|EsD3?JpG{u9i(xkOb#Hdpq9gJ|h z@9~vkx%r}C*C`La74`X0*)aq=L*kvx3sWU6Y>CWn$UNZRGloae^1NDV(RH3^oZ*dy z^)%bt|4_DcauqDm4N9|B(ghzTXI4d48%R!nI6}*#Hp+-R@2jqehcz%!tZSlr{@UUF zW&0}{yiCf)GLxcXVp7Y?K&xu^He!TFcwu*SUbC~J-f`JalzUWa@sk7RWa{0!BFD@V zd={!P|A1Xqt915Rr1n)rVIwvbMuacIM?QnrFaZBoajQirVrEkx-#|bM8+pWMrK}mC zm|&EnZ_(I`Z{B|6?*zX*U+la|z{3No%`2e4W^dO+=170@nk|wh(%a^XdFbo3NMC6` zsr=}vFnZ5#>)@F-MhQW-gl~Ew?0A+FmqzE7l~KErZd!E(FQVU?C%w*!1CG&Wj#p%h z1XAK~sAAw;1t(_bpDSBlu^?@EnE~qtu?)x@wYeHo#F5^FFHeZn%^Kh2$ZVNK`@p57>Rcw2V9I~i!3W}RX%@FP zGxQtem1w(Py~wXv)W*dY{~&~aMq z6{pQv;@;qCuCv0B-}%sRsI&ik#j=WXtK#yL+-2qGR#^}~@vgeX1{q?_`Bm^-8&@kg zu;*9pS+1Dr{a;JZuUY~Lo$^w>&$)^hxnpSA5H)m2eXaoH-P7}XNLuOAUhrdak6#$z~Yhtm7D ztYUiG*X~tI^^C$WX35;!z9z|Oac^E#D^X0OIA3s6-Q|bnhj8fc-`ai@-|>nF)c5RV zyH~|Zh*Ki0!e|8d-+%hRsz(H-yMXZyTnnzqy7de*4O*+cNH79s&nmrp&#HjCR{gQw zQp{wrU4+dIIC@)`*Q)oDm`v6$WZD9cAEL1}DA&DfRjs751hYPSo`0wMW7~k2u_8j^k@%L9 zUa}Taf^(<3NUs;ERo-qQCVIbEPw!y)pF{7RijAvvfBsWOIUXj)GjfXfg*^RGE#e|< zj4jI)AXet=velQoNho!kKdF~&N^W5w=Wju6wUS;u-s4HyqAo(dBVmiW*v2R=;m!v$ zu@ZbX{5Kg;`tHc;^*S`f6BRpEHyH~3B23IQml)BUhePQ{^L+1BXp6GN7x8pBlnfoo z&_we?q30sf@FUrDZYGO6R-G!ZYuu%MMO|P^YC8-n->OY$qt@r8;lp^As@2k`wlpmp zd76qo>6??3(Fx!9M_ZDXUq&mAS0szIXsOj(T~SwVh6ij{fkiZk@SmCbAam!Toy4RO z>sO_?DSeE0?SWiwG^ZC1g@Qw!tHPoC28^rW!5na}7QErmJp=nzQ7kW%EWJNp7~_R~ zVBtb{rnqlaqAO8~vnRRf`+M}5f4!Y$bPhVZ=9JaC!=bx|_pKtvB+01|L|={KlH82t z6}6OXQSY{4Op_VAlFu&U-VWzNH=TTCJq<7gX6jV1tgO@YuVrg_AKkDWW8G9$u(K=@f-6GC5bDTu_a$FzKI`u`b{qB zuELhNis!+b?72>7SCx}dN*E`NZ|fz_^Yfh>-}P9O67az}KjStMV@wej)U%8wpr#kr z+AYp^)bu>1*(6%T)8G*#POuZTCyX#1d#7)^YG_TqtE6k*xaP%He%$E;T%s#lmlami zZ|mxM4x<^Z@7TZ8M>aARZE>}o7!eg@h@%9Iu{*|WcwY#RW zJ*C&o%?;X5VHGRlb7Q4l4rWLHCo~R`=mopY$3YHE9iNuE+d)3DLFPN&qnpI4{B5kt z-G}^KTxG1v-p8uUZAlns;1SaB>|w9JpuSTsjn*Q@4DOM)*=`gqT`WgA2yI0;^s6wnKT@gqhpBA*oo%2b@TIlyA*J~= z-9VdpW2|vp(Y3~ZZOIVq`Ie1iidoZA#whMCjehAVqhFdgwxLcIwlBu~tew_P+wmTr zg+q5od{}SMaRi?cD6heoP+AdiDL&1{i6uW}x)*Z_aqc+ue$CwzX5=3pxYjFfOmfoL z3uo5}Cv(%dyMz{JSN_`W`Exh&8#M~2S-~(<>K6-vG3bM^=qt_LEfJoFmCT}eoZNI! zsdI=~X&e{Cv#X3{vxEIaX=XD1Tb{2P?TjtmeO1=eHeGKQ)rs7;aOhB&H8^)8)46>ZgjE5q#OKt9{No#Upp4d6p z&!%s^TJxGiI90ZBu~u^$ws%u>wL9=u*~T|gSNA-fM5dJeEcVm$H3uBJPYi+Fh!u&> zGCO9OX=943m^rzqJAFrEV|RT*?AaTN8Oup^hOiAY^IdgD-k;_1Vz->THCvp9^(-YH z@<8|>bJWuGR4#YnV zTXOE2QbHy{r;aUA(qqoAvpgCzpeeM8e@2W3r8lJen3>_w_~BjZ<2G&Z1c^|gGLJLf zl74dyo`pjRcz63W-4qL+)*$z3V62OJe2HmnA&u`ZQ5Zzar)S2Q5x<-XZi9$_l4@ z;fz+hve`qf?s#;yA~IB}et3xH_@JAFLk|t@1Rm+SzXj<|U^$w9+y-1>EYmb;qny3= zg_g}_KTlHJ2^v2i91HFN@87_z&co`s%EM}k{;-;6Oz3}Rc&BmXy-AQw(p3P)cTa1U?*kcaT6PzTbxNt>To49AnM) z!z%43*3$u!bus{pWD;~O^73Q$E+=t6HntNo52v-h*M1zn%LFZagltJyH8-!tol9jF zOa4+SiE?F+!N>m?WXlLXjt_a||9I>Vk6n{#%m2_uvR@6*+F0wj0GYa}x9lKFCECn8 zuHApIwY!y!hAieGDAR_qsWf8N-xTp)yfO4VJSCfYT?ZL_Rd|pSm-p~VmUW6ec|)ac z)72*rlI%^r>kmfD9)q%P4@66z)&9ff{&o1Iy!03|l?#Z9UORc+M>0Fr68NYw?pRE0 z{RUYZ}1v`fov>diX1Y3d!B4OdCp2s`lXDanBvRANI>lz2P?*^n38lw=bAC z%*Wf%o3zH>H={KwZ;sIAa39Is)O-0&)3f15U2&{^qSw*Ot}$;ucL7@bntpj?ofuHU z;SetHu9Bx3K2sYSJJe)*hiWilw@@x@8krp=+pgqP z;Ta&e7uPjX$T3wUXUy4c#f<5>J1G~<6i2w|P^h=>qGa^4(t`3>ZI6d0A zq{=?!fT#LK17|O#-UFi<&Vyg;=5OZSGL}DS@bxfOHN^~z3jMEp%kYF)K z-u_I`1sUCc2K4fL(SlXuk18$GhzR-3+{>89v=*#k{U6Fv%J&D-jbtEJ(R7p8vuIE3 z)!#fZy=jlCvC%d?i?l_i^PiY9^O^18P?bvGF}o;sXe=LvK>SwU>++{M(iX+Y7Z<49 zMb{|0Hqmv8=;3z38ugj_K^3erF`ua?UfvH6GE>*C`)OMRV)l#DPOADmNF5SmUaH1c zvi&hvraRaj1}bxL6Yb+b+gxp)pRIeKf9sWW)8sBr`x6&4z|O~>9f`5Hr@7QvV3%ay z6~S+*byNg1O9oy9za7EpsBdwaz2OCDKl2J#_sku0U<33l1Mo4L@(xC+Wae~@PK3r~ z$X<6~-K{#dO|a0?2OzP}L7&5+sRR1RlRWL{Hm=Uq#MaU0v`u-~!8QXn=m`U!2n16{ z<1U3@y0BDWYM%})z7WOxsYvVM2L4;7<^8(v-3xhJhihg_H>Vo%-*oJ6xk;SZ|Fk+M z@@{_`VkrA&ZLP`wgDQCbbir7>U<0cttRDQP;mxSNLU%6`>;4NVcM2v=a4e|($-Wo+ z#v+bd=Hn3(@uID#hJ@rOhF}U6=OK%u*hmNB%AvoVGI?tWh zMMh<%Q?Tk(!nV-5@Ra-Lm*15=@_cdgI^8CbgNJ2Tfd={~v7Co(D6jcZ<6vmQFoSrC zaOf8*m1lY&lTmu8ydI0;nM^EE4Vr40RD*_GHV~EVM&AitL&_4DqSUA!^skVQ8oy{9 z44oYUWupB1RYANIv65Coeu>s$z4M|(tydp}e^@smCNpNp9Q9FSyqL9SFm!n6QKLyT zi$kHg>UdY!NF}#xjo2X-gDVdEK9Oc3Eks&~R6;5ttwCCYbU)JlNIyXOK^$z9Zb*2L z`;u|Zz?F{6kQokjA=A5%jL1K9j*vV0cRrD{>;_*m#HPPGdxe zd)WN$I`&awjvru?({t}%k@6rPT(5ylV$X*J{cz>!MrL}odY^rTvWeGaSF45ghu5#} zVeqD2Ev`HtAeQtS?UT+nwyGJ+T2)(Oy3L~+O&&Ggq#NMIFu6O_+vn)4^oz~N?Nvw5 zzZf9qvLZ?YzY9~#R#YdM(el7NkL7_o>k&6WY3;n51H{JzmU38OJDA%;0ZX|PbKSD+ z$F6(knafXt(?)e|GHEc>G*DlWOg&<`_3*~Lrdp)wMyJxsSx_4AwUElU=iS(u47&xn zAG<~K=qOk~xwy}x_fAAF(>!d28ZYn;Z&RBE;tK}5zPfcHBkc_z`^DtH)@IRwdHO4zt{e4c=kY4Lh z0+X}P$C!qckS2SX3NMfZosy)KY=T(NJ)kQuKKfzAg5 z(x)K9QW~SSh)$}H(F?q~6IbkD12}Lzq5C~!ipUO9SM6X<{bP40cZOhJC#k)1eTQZ* z<}%%*30tVh71CWz3se^Sb`V|HQi{5cB#;b5;zi=R|BTp)f4)y^`q%r)>-TCTUgQSE z9rJLk_9pvGnww^`hyGE8=-TTPCpq}hmrk}3QZC~~*;+tsnvJQJi%-F{f4*elaW6fz498q>R zg)i$}w;(Q2BhK?8LQi?EkJ&X6b4cyEymC7tQsc1$gIDhBCz+sk8g--$tDHovJ)eYR zqu3RR_hjK;j%(tT7mrpJME%7YQIO(M_gK}DuIXmSV7(rDpxok3krKT|smh@_wbOk9 zk?oxK6ZrX3#X7{~HeB^2=uUDmhqZ~ zB19gIM2xqoc2h^A+5MhspF_QLmCbj`Fr%zpC^;PZ|Z@ct?J0$`y zY#BBHW4DkCt|TL)lHVy(DKAbdQ;S zU2vRcl9He~=$P70z4ueXKHz2gNxEvR3TwNGeoOhF*DTdbuQ{?#os(+aao%&%S+_-6 zl$MYgf5wu(EX6(lPWL4DNIz`i5_dQ>Gh8MKk)7)l7qsLI_;J+cNw6r`#2nnu3%>7Y_2C=drR^p@uUYD1C2N{eV+ma#`x*0d?j=raLx+JGN7W=lM^%~sR17>leC7e5{ ziN*m{7SOn%$^t)PhNd^gxpSL}-NZtpgenV?+#z`hE*;i(L@4hdh;zaYKmFcgRX zG8}S;{}D?$G3zDx?Wmoflj59vS~xc`M!)&zH{1T@4ed3>&cv+Wwh-w9a0mu=9U8Nl za2R{P4lIOM2)k%%c_l&R_LSO~-9&j@)kNa1;T6J6;zb)`%}=Y4bH0|qc*ceD^8KRWv%#?tooeb zBMBn0{-~oN0(&dszTQ$F2CaTwe%PUlaH3P{jq{ZMtX@CHOWk zAwquC*%wt2RtFZ^g$OzQ!(m=p;h;7CN&Q0R^KVW~@RFOp{G_6Ma(?%+!;aJb?(!w+ zUCWYH#+q7rO(q!^<<*M7|Cem@ZADD^D9Y>iLrYZN2S+8!IyFmV_Ru{a5A|tawn|#(U_8(5P8gtIkutDVnnxL#hrFqO`iW#?5)UytouQj4{kwv0;&Ic z+{D{0nPRCb%*Hy6)%!oeMesj(9#(Z8E#;ItNG1Ip`esf!*Md1{qANRN7HmwF6SKP! z(c&X*zX@%pIXxU8tw4^*78ho4f zdX#7?kBr$6W8?hiB?eznZ^1dl_w!c8ugWnl%-!-buNRb}D~2C?lg?#mNfN6gvy+q%CBK%YwE0N8w9bWPaq5d29hGZFiu z(@0h*FeY^{v<3U8s84D%Bq5vc)FpEFbKqg`Evtrx;aNym

KWX05IHj}A8Q&N7o2 zl$q&5?!@eixPvS=|B}22vPEk-W~>kE+8?oZ4kPt?3%iTz<}|Je_L4cVcVgd3Q|!Fh zyW&bdQ*%6r(Hq8MbyEu)R-oC(99K^{=k}c3RS=Y0!Ebq-D?={=;fSU>ANZF!4)Iwu z=I0;#Dt?LGrDXD_s(X7atisd^L6mQ*j|L|tU~fk*TWggfJ2P+o2+=H)KCe}oy?fH> zTXsj#51uQ;nhV5y@s6B%?MH*wgdh2nkQx(i^B)ab67KN77PN64jWO1e_D;=RE$o1h zm#=tuc0hNFuJdScN`e(|wuJ6LzQXWq9dLVqt)*@FTi~_eTv)Nzw8sXGvH88^?g#px z?N0_32#`dz!qMP^3D|`aq;^(jT7Iu5|HDRNuI|iNSUz9j`F1%UbG!}zdj6z*_$t}d zbn0mEiG*y_w=UsE{I5(f1u}X)D_&{L?=`Mym5&Cq6A}WQn#I5++h*xHzaCb8>mOQZ zdnbwyIP#Sm{tZCglyDYMB>0nR)Vl5!Jb5@FCQz>_Y(XnmjFd>${Tgp1ym5c~hODD? zc~(4&HX8m^^y2n*HV?QYXVk; zmfa%7L7|x3G6%X)cpA9Mphw*G`O)A*37dL19*h-HUVefpCa8-^$P)HvDZ04KmITwW z%WND`W)A#T%|H}D49jFY{QGpy)5(z&k}!@ji13U_QsNVwep*v<3vb~p#~krzO}amH zbGn$*M{pL25uANj!I2;%sDU5llN%`{kNr?ZkZPElcNNgmd5qN~#qf6|JmQLP*)Hx9 zf8Q;{#B>W<17=Nm(`_Qju`5S5|0w^A$kv^>P@+tUc^7ei)|eJK-fNuoVWU-|wR|Zb zZ~Rm>?qzD-E@n@09S=n2qUYzktoADHy(k3)~bbk^9|W=Eennt4^}bv>MyB$YsDfqzAQ> zDANSyW~)RkIlBtx$TZdL*i}Hk*6h&*4yDr)G&^XyuygETrgOi08~vOnoR=59N`z8e zcjF?h;V{bAXNuFZCbZDuZy%s!dfLuspcZcR%} zFps5{r=2Y})5?6<%=&6t#;8f@y9)j+cfzB?-2A>wYiB`;@5oluNtv1US}->D!^VL8 z5oQY`j0zfKFqdXOk6pcHT|yhElAkwsR6xu>bb+~JguV;rzS6DJUTgnGek(F;{v5!3`dlAJ;Lj;7BhJB%sxKti$)5;>?Fz&PnN>O z=Fgo7?&rC3*pq)n&w}su#B{N+m2rVAB{2pi_NQXJvGc&UD%+cVY1lq^B;Qgz)vyCy?1?@4`x$t&y z%3YK4@f(|;fAh?f_27A|;Hexy_gR3q3%x{K2+SAzDcva3&Zs21r6Z^MBaHWah zilw+>bNs^VD`mDWZT*j}u>ltPJ6r3NQYGCE1|t;?Z5urKWf5?m0*o+zV7*9h`9waC z=!K%*)}oSLer;Q1OedKrokUkR(D0XnXWv zP-Rq)|RdvDuS z@S`tnVnW2`Kjo6@L~P*W=_1uZ(_1W9i|8C4E0%P9vEGI~KW5Ph8S(MHnC!#i>@ZmrBwZ1B`$g7wnuJvN21JsdH6as`#*F& z|4MH7y7kGIzH(L^{#tyJmco8YSNqT9m%g&&+53@_f6|5^R!hPp#`w}#w^h9GmHtWN z*SaV1Hu8n04Z9Zx8@?`xd$l`W!^{?D9RfG(4ovq>>iTjmlbf3VE7+=U5N$55`+ctV zEApi6YhBz+UuC0&KS#>vI~u>{pJZlw@LU(v2%o8YagM~^hWVHEalA61BF2r|Dw6FT zY4ij?C(bh1@#z9_sYrGe0hh3C2W|0-=}s-2Oc86wzDIfuq=yoKN{{*rG_GeRzPHawpfNEGvb=M-ATsUNbcTYKs*aPUe*z1_D z_dV-KLVQB{dS*JwQ3HlldK!r8^niwL5FJg!p)l2iX2d`bjo7HF8zb7D_Vh4z4AQ6c zt)X*a`RpcYX{&@SWpId}aPjOFS&tcfsLuvIco*6=>MVt%c8Cx9NKX6NUtQPyo<^*!0Og=yO=Hhp<5F(5UTI*DQ_$nx;4Btzt+*Sj6c~FoS2Y& zrbN_r5)&=+KT$*P*^e>nZ-stIThW9aa_@EU`LAGII4)C~?(>_(Vo^akI?(9jDASeS zv+V1L#$`iKpB?FsP2cP+?}7E{?mpwn<>lKQ*jG}%Q!UV^L6bdkNoOYJ#i?7=0wXMI z$|%&#ouxj6`}#UzAq$5V^%3KzvO(;C?Tj3un%OAeG93B{dK62sV58@_V0Q?<40RC8 zbTLbGODGTfUGKnI6coY$p3*Hl%BOpy+BJ*u!zl_!BIB0Dz>ZROjESVjkJ0nRi1Jiq zR|M<>Z_)VK1jJfc*C#1MkXqk`9#51i*!H-NSQl$ft>inc>#@T&a>83)bG@z~?}K=M ztpgTO^Vjlw&^i8^OfvL7VV>K~D@-4aivVqPAjS;(U6NbhTn0HQ80eS%fcpUO0_+}g zcyG|iEpjZHBQ&o?znM45q!q?+r~}{XI+&SSm5Jl0Tn#XF#AtEDb{mQRi@A$pD0e+; zrTtnskc+ly0yNHy+SPF4<}vDjpl#Co60sYA$sO-sE+rtgHswr$s}4H=NE!BH+?r4Sb9wBx)Vk8v=Qh<#mL}H7D|`E1 zg&%bNvVly};vCbrHjl65UTjwd)cS-9U-7=tUYsW5#+w}&<6His3Z+|dz6*o0m-kKf z;_Mpu!-yhnCcxR8Fu$FLOnC)XSYC1T@pY!z6Rj89nSI!2gqV<@FCs!MuBydE`18I0 zxazOp&sjo*Fs>;}iSScgU*Y;Cu4Y`W`-pJwcfR}QGX8h@0o2Q)jT($AQ8b&mI_eYQ zYL|7E^gdA;4xJy?OlZB*S4ClZp#Ku3r%IZ@XOb)5RDE_4I&0kM#AL#o9)y1@JWRi4 zxzA+Yw7l?IV8xlEiY+3PLi9P)N}{vAgOZBl`$M^((ZplHNZktKWvt<%E^l`d*gyk9H;bz z|AP6?D_Bo$c4c7|KjW|RbhPrm2sYMKjm4Qkc4bwSH3fC+w>iiasS38|rp|nCX9$J5-{l)+8TnznpR;3~A81-CuGC@=VH681x0r+YGGcHr^!S$^%Ww-psj?>0RrLZ35o3Nw1C@HRND z&R?zk)LGq|$5r=o&T7QLFnKs%XZk$I>xiJ(BnPzniJ97H;MMDjDU}_eAJFn-~X{{Xb6Wc57A!hxxZeZ=kweh)^2|XwqMPDO>H>z7jSwzq;A@q zw~&V&(xchMDX#Dc)qFgZ{4MmM2=svn^s5o*R{_0QXIEbK2%ym4d2m+Jw_i3y>a}y* zFVNDTkH9|<2;;X9FGV0c+@=V`20(1^YyX%GY$S&@B5%@c*MM%H8_E(X{nk)u_^qV~ z^n-wY&~G%~S~PBwcK>k5I}G^!nit_qxDH<#fhTKAFHk;u3*hhUc&~B7l;U>Up1HW6 z>o4i`S8~c=FSS-=-TDDIq;dftARqy?TU-T*;Puza1_3Ac+uQD zdbhp_s!poC5S_Q7xRa(zW|pQXM~@|Ol6l`ON3|B=SjWKJopxoAa?%lp|nSjI(5?-BUbZ5&%W z96C0%687j!Sj!*iw}}Ge{7Urtm8O#3&u3`vgcSp6JM5+u2ekhi(2idq9qIqR;eYg> zzKe0`d^pD{Gp-}rKUN8xyWWe9O1PMH`E zo$8NzMhu;tGBA8aj*G1N^VTyt8b6yO_*Z!0=io2NMUn@5F_sK`F1v8zhykN|5}qk~ z(w2cgD^tnGGem9pIA}`RV=AmGmS!z1>hiwV=7r@nS>YWLu3m zrIDV9fHQ<=9&og`kV*B=r6I03)?fDAl*WB4sZR*;{GJE5M0FoXJXRY{KTmuXUQC>8 zL(flm2Js}(uO2h`wjkM$$KXLaO??G}XqdY4T?OZ!xBOyEV_M@LoIq1wk+w3;ORepR zusqQ+mJWamN3>4MFU~!m(m1B^S;qwb@(Lz*!F_3shx?}McT=2LEKi@8l6pHgY5cL- zx~&*2=9eTZZ+aJkqYRquAe^KUF44(;os6v=*K#JpJ7f6#F;KzD^x&97P-Eshl_ zy-X17Xv@TY-GsY3$dnTJlz%6@ zG|_z~zYdSW`9!?+IJ{Dbn%Avers;fC(kQ&94HR=ZKwFsHp9gHI)oT%>bIm{A{pd2p z*;uxzE9|3s`Zz5fJwP1p!$F6*VTy0wao6 zqc$;WnnlD6Vst$c$+pycaH$(%3R{7=6_2$z2VDQ=$j6mlotXp2%W+j0P7Kr318 zJ%II*D(uGoMqgOju@`3t$!}0!v38T5Y;01GrgUhMhPB}9pZZUI=kwG@nz;u{we1Y~~!dXnG9P!mQ zJE3F$C@if*^N}!;;u4KDriA2QFjpDM)%8fxa`-s|TCT8qti;7Z%e4m@vALL~iQ0aU zu#@m)!+zHdDn~d?64G1>F>@}yqM?hZ4yu5s%Zf1xpC|a5t*_S0H>nx2Lvp zvWNJoiLBN|rwHuM9S+;AQX@XKr!*2D&q^cl?;;-h{*hIPy|?^YifqBXm#ACoPAqLBjd@RDc!OUr{ZbDn!ek&o)Rb?*8%DDgSNs1;;_lK<7LEjP+M^UJdZ{!@9&dK84FvH9dx!iKQhK*pp6!1D@`*mRG>?L7Q{2KTQ9*eVeN=M~}NUHO65s zSh`CqtsXk_%UoRG?NDuH`mLG6fd?OMd6-wv%<<6jK9AW*Gm8s+18Xoe!@0mIZ0dW(9=dwm}!-nT?7N9iwj|q z5YSx-_0;8Ve8X+@^(cJ{&M51n35^Q8g!{0BEaiF(TAm^4_0X68{PF?#T9r4t;CTn= zJfJ^rKwqoR##Hj@yf+>fH>TYmjrTfS(6&xd3t7VAE$`L$?hi)ak8?x~sDu%$f_>!* zY>|@mTu7Sxq0$<>W2rxQYccA3mnGEitN3iu9Kchx%GpE~%XT?xtJ#@1tGRK1@ylfW zIPc?U*vLA}Y&GDz!@@0?j=l{&!BVrlBc2^!|DMAHm=GtZun=!K%QG_1`n2;LedBYX z_Z)8FJMZ~txCt-IyfLAEaYa+TZ(e#mH}3pKS~X!f@hd;gPiT&MISWBb%08HS(mMoS zK{6A>Nz!`rggtct1;De_fYqrt$ z638uXMX3Wkw4d$#5ZY8`w-}PPe@OVj?PtU%E4DxmrcZa#LFnAu_F7aUxyjYI%M)Y7 zc$dlY>Z%1UX4&OB?TTNuVAbhWu!rDUuzL9FXsf=&CVb)MtTC&y#RT*)Vr-Y|i55e4 z4M>wy2HYRRu3}Y@<*xajyFGfyPQw+ zIRbCMN(Kji#MpV3Nr$?}xsV83VaXDG)WbYfY zzD`?W7=Mqf&lpyGPvJ@D6`#8Ok6Pej(M~gc$yTJyJ*X`iJbewMB+*No!`K7C@`OF0 zhd3L){^cOP*z`c>=4;$o%uW+w7y9u(D{O&{)J5fqnD42=o~bNZ*;}5&tW&?>@3V~Q zZ>$0B^kL}RVg3&i^pGwp7nqd=&UabGQMgZl4(g7n#C;(c^jcnc7RCyjVF`kPo*7xo z(r} z9%;h6;Vq>r!}I3va)J9LC(WEc$ObpfYg#`V!PQ7MNett;><=AeFXXb1Fg)0>z!+>FHjM=&$Y!5tPd=28#|>$hWBzwmRVPA)&*ks_Acvch@-p;qht0 z{wAA{zUl{er5J80ON~0stQA$-R(<~1^GZfq|O3WY2wyOP>_R=_e-+}o^^j) zPxI^U&=tQM&%bg*Zb6=Big$6QzxuhfU;6N5P!=Zw7$PUM9AIoq7TL3+} z8}UZEv*E=1oxdt=iIRh*JO3reJ;*T+b0N`n!v6uJpzij~sWeUEN6iHH8#sq5bIRVd zsgWG{2!CPHnbJY0JuELa?Q-vsmzZ{~ddhE38|TxF&Zcyxt&S{TKIC3MMcQ38`;l(< zqc!ppTeB=;*FNlJrX5ookRvftYMf6U;MEjcBhR-(e#y(3E+gI$iPs~foV&d$)3+Ew z6C(`u7i@_i9E~db%4y>9nlIeczj3hVL@>UxW8VfBW$jOZHqa@Z$1ZR`N}LNzHVYBX z!rIy%{gu3Zc4i}CtAuf4M4nnErf)KeLpH?~-~=;;;&J9>H`VX1-v(|g)`G?S?2GkL z^_v}WJ`1P_+dxC0la2!gftyIOn1hwGZh7bL9SO~|u@$3ISe|BO*q z9plE9RE)3ZWbLt`z$d@mxLcttY*y;{(x1L5sbF*!+J<)4d98wK`lse1z%eOZZ~5CX zkI7cgBG~GQ%7&eVz$JJ8GXxdW{eHIx&@yC1-C;{UqZK>OX+B~uU{&F~ zg2n^c$Ex^%;{NPDFAe}yI2TaiN#}OC)W#qDPdh=2VJAqHW{B7cA}ZiEq+ReY)`GS< zQNOWUdNJ*Xyuei7c5?k|UX~u$LZ|31UH`90w?t_f zxEH1_U}091@S3~;PwhRNwHhN&T2U+o8WdJ~zg=Erd)!00q3Hw;4PjJt4u>SJi?fm? zoP{=6N=#`bh};c~;@>=fn1NA50rTAH&;z3|1EYwlUl{*~dXnI;@SC6g4zUCmW!6ti zxcXnp*b8hTTn1qidw~_4@$cPIhIfQbWQMVc+tghGtTLRBu!$1nqq@1tP5zQCuiwf& zE#bPd^8w2LuePS{^K3=W41mO}8(~OV*wbs76VFB&Hblv$(tYTy1x7xg(p1ZfOzob> zJcSx`jDEiCkJy#UU#!q9W1(AC8Iam)!gv4#N zs4qv4-v$=zXzPSWAVVGX02EC48c%pTNcZ4-E$t{un z?N1tCmen>olf!hzH@56sHopFa`yKQ45ftwv8^SL-_EoDO?ZEijYHrLYew^$K+GPaE zz)Oc+;3mdW3Q{dt~a6^<<%BKRujg;rt{!N+}s zNFUz@5+wNHCN%qg8HSj$39=Z`B!J8 z6TbJ7W`WQF4bML9MnkoHuj_*!`m(+shyP#tfoC6ClcsM(SS>$b(_4*Z5$kk`ZPxX{ zYp{0rl>Q2^74Do{OG_O$TT82De(U*a^^JvVY8Uq_hE=~D^$q*n4f5xQM;k)+Ivj;Q(+#B@d+OJEga}Qt>pYo4hknK7zv4sp;5xSs*c$PaeSr z%_RIJp@TuDZm4i&5tr?AsmAVb40g$9Sn8~ccD@-FNOvUi)?@XhE|W{!%3IZ@Vpo(^ z@7nD8)a5#=nR(Vv{1VN~Q?%aM4YYLz+W9dqJFY@ptjINWDMBvQ*wEjrN*(SMkLawL z^(1*53FNmeWCnQ zS2#E2q*%`Kcbw6e6dE$&F+`bp%8k(-kvtMJL$AlGY!A7uoLOa=6^M%6<2t{J!TkOk zt6E*N0!G6dt2L%-nYAuTAqN|T(-a530$>Wo``Fbsal?l6n7xS6yu#ZKLb@{ zaZV3992a;K5*#GiAC#VLWC2H`+^_+DCJ3&!p7?@=(k;!Km>oFts~tK)^t@i_hTi7z zuBmbgb2V~PYAauMXin#1rfIrhdy+-B-isL0a)Ph1aSaat$p@WpxR{CX%OUXKLNvcF z>H1N^ayM3TQ*_nBH_rCxhQ9 zI28F&su6|=!ys)3e-GVN_Yi4_~I zCVy9Y^>tXA+Xy`$7RZ3@a>zPCc41%(%jnZ`pz;t(k2-zMSRty>SK(6C18c?XM$%1D z^&mgffX87KRshpB>f%IwHngV_#|lRr{6~X@n?57P+=RWg3OYh8aG{&_s<9pa0BjJF zjz=`Qx}d877OH-XBMZLJD>={XDzz3z0Ew5W@T>Qw08 zq+avd9V`{n5Y{rMwW`fu1NsedF^}{_7x9}oczXfQyo#ug`RIp#AV2Be=%G71=>vG; zsUrPV$^-l1*g4_^NYAH_YGetCwl3+-&NxUnWsSN9y%*LV$8&c;Q!1-}BXsOsSN&O| zI=#@7Nxu%RDPKf(Mtk*PiGTb9=;+K!*xz7bfKydjQ^!UXdY_RKZSdj1bNj!%z-NC6 z&v`5`19EHQPIIrGy}-}QMIViq`AWBtE1ZPH+@Vkrom^_|4!x&Kngu=(JMLB*SPpWYy_JH--U$5<;s?Y3Y9%i~a?v)% zla(ezkANFHv@$EL(;ElAuMEnTMu@M>8m0G+oIcPtavB%7AXk7dl;=%%rWB`&i6UQ_ zl|IGCMobW9G+Km}fN4jSz&^hE;|r=s;xOmb?L)YH(mnbsdN%6=tkb@}XiwItA-<6G zhY(+R#B+WV*+}5i2YPG85jY8BS}llIdAAp8PM$l(lBrCKaME8Yjua9FSc?(9#Ko+i z;|pT=Kht;cpZOJ@JW!(cswwOpW9wr^4?9+Ln#BWfLtf2VUQXZoCmrf(*A=b6#o6ylx3HsfM(KmkjaTS}cyk$A)RvPcVeDviU+fChKrXTm!*LQUNZ&>mrF3%&gV+P;9u(k|-x zIRcfkXX+XFQi?*V1bj`Kmvk&n`n#knvLF4XQIk)yLF#kpeYNnbI+EvPffXV29As2g z``L?-RY&^_kmiK^)i%xUvlmp5%j)h@C#g=W_QNL?D7oanFZR%o2F=^xp(fA>G~ep! z8J)d7P4KSK&O>+8c!(FP#TH0!F7jB*i#@x=$sTBs6~`$(OLx@AdT=d%9Me4P7e9{a zH@6wnA-8J6XdhCGuj%w(Zx9!H5>P|S|5*d~!hIh8Em#`(mpaZWb6A=Oze^%yK1$%4v6uPmu*q5pGT;+wqibTJ{9y0)ChTN zvtN_`zg}(n*FK%~gnvUKBOV4$DDqzEf=`*RF0gyrBJGa#rI#mE)OyU|4uZ3fe-yoS4DGHP?hwLSK_i96LiHKa%4%;}>-?uby_|cSVyOSrN&XgY!WI8s z$NNq1iUS46TFizwovuEfy@h>2Nz%JM#hXE%1Dm+)1Lzmqt;jGZQD?Mv-RMaWdjc`tN?8TS_|04k|1fcdzh1ZnaZgTiOxPn zpIlIBSm5`-N=f3tURqzzW_ke~0yUFMPYvS#rU@9p~L~@jlR? z|JX#nDz!+C!~7L_7M3(-1#pikDg8Nzpd3 zbsAFa>NaA3G-%+FZS_Tm@&66ly!^pL z=WN*8i_61Vk8$gg#&yE;9#38$mpV&Jtczch3%368g4SvPjxX4#)`4D@f?Dknn(tG8 zk_YCU@y|$B2eoT$Ie*8u={3KlFVwu_FN6g{f^7&>90os^*pGwir2Z}Z+uTmt{l;P^ ziE1HP)zh2E(u4yR3yxnR9^3P_rTBp+hKKHp~JeBQ70 zPA$f`7CDbYjwko12B%6m?@r{6Mqb#|MtysmmWkVtavM^5(+*WSCc6%7M zP!(XehxImd*B*zi1^cF>6m|gSLNoY}IQa;U2;!uo9ou+Ry=$BEs7n+@q(lhBD?F>g9Ud+;w|^-+t0lIlZB`yl)ysv;8Y z;A|=2nJ+2)!`J`wsV{$JF>!48v&jfy@S{{;WUE=VIpPwSBOc5_xpvad59 z)xrx~hqSX>Wi@$ti)Ecf9I)=1-?}dB|Mf7+$%V$eT3Fb~i@b$PiC+gv;b}qXZSa0z zuMFN&Sjr8>27RDmz)V=Ao}n5sO5{gc#e_zyv(y3cbF7<`->`yz*Zk;=<$7z|tbx2IP%lQ$~T=&XTOCit?vTXU9~OiOxcRiIEV z(Euhdtw#Ml@D9gF_QUSDg7F>1+LZEXjERc%MTj5P=?z0LAL9(tLdq~G?deg@AR9*8 z)P-5jQgcWO?>4kEzGmvp(CP$Gt2MrG{VM}cv)rS64RMTlcetgoXAJlnoX5*IIQoD( zp3FL=BG^X+g>*@W)FJDlz@U74#U4!V+ zPiN-3;MHrY-~h(9K?-2a{CsXJ;Y3#=8t1IZ?&u4f!F}O(gWB+{;&&tl`@_pU$#|nS zTekocs)l7PI4r&pMvhupt9ry&dp{!cr%C*{BI#mNxFcNJiz0F<2*g!Qs=moE6Sk@nf9dNx(jX(u3U@ ztu`SW-eh-*bK5uNzT()|#;IOwQ>pj1skxob%RbFCf-7vD?>NIUSc*5BD!byBsSo6w^WoQtrErsW zIj!OVK#$NZIZIe+P`axd`wC*K6t7SDVxjXGxZ-Vo$_uH{{JzTfPWC#);n1>~(CgXz z-|Rg9U0#CuaI+qopKk1A-Q*L6=0~n(-y7PLO1ixRX=Fl}JNQ;5R@~0q!wuC4)+1}HjePGo`CH?Hw5a{b1du3>1(Xi=6 zgU)Mb+@&Cc1OsfSKrRfj;nRtRau#Qo7L?z#t|HVwwi8?xBeM=qt6kEsITvHmzuOHS z%OWSs{MdW`AxI9bsBj+hYZXdF-!8&FqP4IZ3Omr3mHqB6tU31iuF16aEsB5FU0h zVipv#tM%@^?Rrg6`g13^^Dli-XlPcSSODnVjvjeK&OsQI&MA_u@^klq@}g;rf*>Tv zQJIp+??>utQoekxi#5no&o?M!zXM6yb;+=;pv+0cp0 z{~UMJqP?A(cD;Hbs29;~I(8a(+w;zT(8V&CK6j21Uvb@8`j1S(gO%spcelMkCW_xl5f z3}OsuihYKbi=XL+eie7$*B4YnQVSYkt?IJ)rE{3LGcNJIcjHqEUYl2aVwLYHt#tlko;`#aHx6L&*d`{%ULYPL> zPd_!}yP#@J96ZPArXP#zT|0oQJ55MUX9CS{n&*^HFO2bU6IE$BkZRh=>yOdq;#b8xBRo=hCLSRUVG;@_?ly=I!X6D%b=HN=v$j^Z*p0>Ip! zts97aLo2BF^ROFa>9AnNs`m$_ncX_rP%r`(4@%c?Ryt84w@Z(FGAu2n33{ZN+@0f$ z1y)a56PvRZL) zf`=n}EgA1CC6cCdw$sweMt+Z39Lj|bSn!6d3F z&>4L@3u95@g$|_8q3_7dI_X>DV53j?2sfeKUmeusaM1AQww?8>K@nqVL7zeRCq|%; zU=X)9S}SeoW?yOL(nKEiQs$=*^Qi=*c@OGYA|Ljsa*U=7r|YOOHOfaRWuy$JyXI5n zwEH(C#id_S^jR-KhVX(v2l{B=D_G4jv7$U7ejEH>4S=<(L?QZYdbvf2E0Cnht~PO0 zIWt=e+MK?5geAduF=YC5M$-KOUKQ%~^QtZ8Ch<;fv7;p4sVUw7+~n8=eoTyu;FG(b zXL>U(vRQN-x~a!$mB8K+ucV_V*7STNJ~}P>Ojc^r*{m^Dj)ayyu&2YBRGtAylbkl- z3_VAsUpwVY)ttQtDWZ|$UjDM*j_2`sR^fR9{~b6-ap3#A0QYLd(U4WNp^wTzla+lV z&_l4~wlyeK2RU0Od~&M=Bm6K2rTKvKNW&>~iJK1nOV~RM;9Mp6rUvj0QZ;_=87O|> zNrCL&Ajq-5<)K}B5K6rX|J+%qWuo%NKySRvI@y&aXgw1Yo$x@F0T>tTELFzA($dqA zxM8DYAL-#l3y`qr#{$nOTF`^B&L)EHVUbmtu-=3djs=Fu@Qwos>Z(-)oxv;bVSPhT zDhV=Cf7Fz!@kZsUQ@2Fq770U%M%t%WL5Acov)Hc=LfIvU0}W5X@4KR9EwZeidncD4 zZ?s?Sll`)z&zT0$onl*FzmfNFRAw}IikiTvDCIZUGQxhf@7$Li8H$v&u5}@(#OJ+Z zL9Zc+-*3DMuRt8{84FKx`LF~EJkNREZ^d1QAF$PRcj*m;R)p>TUMk}$?-x(405+*?1F)fMd5J<>0L zhihBl&j9-bNtX6v4HM;FiW)&wE`>@Mw!rn7$JnR`{|dV&@Z1}qr+2id;k}&TEt9-Q zG&P>vqypW5A9dNMR^Y}#3T1N;!+dHw1Uj_7K?4taux|(5>A!ap$3c>2z}H~mMuHUx zLkYsRSxHiQ9BAX5k8fdthvc)ex)u1omF(2n9b`|1r6(Z9`IDIN`#Fx%wtU_-H5{_Q ztp7;yV_e=(;(GJVZJdtwg&Zw558iIA97`DG_7sLCn2L>V2Tp3KpxS&^)IW1XR+hV^gZp^ zE|j0D?|ky=91qv2y7p1Ki8H|pprKRMl?U&d+wHS1CKj0u9|q-{!#lS~`rzR6c%QEg z>e_cYqE98Z@w~P@WOE0GSM7AzuO?Qh?kp`>82?)R!Jr(_2aVYU7x@Af)JbnDsnu!* zY}y@&u6h%xbyZ6WRJrzxTKhi|*oa}Cuj~p>A%6^DxxiDK9Z{!PCai?H*$B|pAsHEd zf3S1IO*VSEZ?i*n@=0hacetzLOVAF^^oqbTTfIp8v$K9xW9S?DE;h;@c)`85&A{PH zrs5lVxDh4;2shVs!2$j37rDIHAT&iCdVCAVkp(8zi5ispg*#t}!gnBLKo>OjE4auN z#0FW<8-vJmS_1ueHUh?H76bOa4#VO}c}2OQ)`D2E2iqI(65%PVKeC z{0{2LX$<$CU5$EU&@!aXPFdhhof z1V&SWcU-4VvY;L9_Tl;Ht5s}7xL+~$e6yWK-V7h8&)d2D-X1#`?t}3$hWv}#eAImN z6^FW0b)9;G=TUoZ)`?dfnW(+AV0XeMjJ0Qi}+`%U{I|iOo z-C0ubS-fzO3Az5!paN@Px$*q>;BkFlT=>?B#x|9HNt+>-%dPbbuc&C5dXw^Ky5mPalx#c&2Btr^vdK{4sA{aR1Mh}-U|r2 zNR~Dn;mll7r+;{qn%#wqOQl#fVwsuZ*BoL07O!uh6fs`?(I~_}(B%d$_J?|H5sil| zEj*&Z+j)_7gJKXg;7>rO3x#gT`e9U*{oMdpMQ;HC*@qQu8tC%l{5%^`CGN{dRsn%}`Tdy?uTOt+;&a8%g?3+?SHj1rPD zpg2_|?SxxtA(f82S&?UTY8WyY&`e+bNf)0P1^NSHhNfibQ8M#fNDmFo*Ax#$FZ>=f zid+R#3i<d?n(Ru01zU<=exZxuXL+(*n zu=m@GXMpY*l8(Z{!)$nuKMHP%TH%}Q3-w5U?jl@*G$A^HfrLQg*FaOHM|vBnG)k(E zVePd?I{cG#u!VgWq%wr)6YPeY*@1mL7gCkG#oh6&E#Ih*^jkPppA%$h2XfZ!CKXr7 z*+OY?uwwY61J;`aJ?iZP$~(y|p(JPD49Le7E^a3J?9z}HwLS>B`k5`nDXR(TKw~KO z(Y+8-TPF$B4-bW|iLcuQ4PayXSBYvHHx^%*Lw>XRFp^_XLym#yQpA58gpxaYh+0CH_cn+J0atwJ zetRf?!#!XZ?hm_rq|4w}m9-F;AU5PiN_*gKw@ENffG%#2&6*Mz9%C@a3yp}s(sQuD zA=C*fs{!~)Ncz5~xp1tP=0wxAmCxNLo9-Y!;(c-=LN&rTgnEPn5gHI05gHL15DrAB zM;M1tjWE&HTMm`{S&#lmsTc(vYMN=sRt^DHr9xj)+<_iIsM*XiP9_QZ74Jn$cR8|st8tfzyV1US+{NK8&36@d196w^ z8(V%aTD;3K+_xHc2HeH_>T##X-5}pp+^KPAgjAbpLb#RDKGXPL6#mKg)B5Hq`Xg!$ z$x^E|?<%A89_`U)O|eflWU8*WE*=1{o`xy({XN*{)T~pJY6)Rq`T~4G%?$cJ3Hpku zjBIDCic6iwqt{6u33i$oEV`R4`Uc|Sjq5VOP6&h6Tjgos z8>cwFCkH%l>_Irct+3n$zQ3jj++@shl9k#YYWF8PS@IP>wJUKDOCC5qw}D!4x2O?! zI^w;)Wt-7w)B@DbqRnVWG8g3e?GCeiFWhXG+r?iEoWOdn4iEl`GdSUsVm6Wewc`lb@b@_@1f9_)Ct5;>= zdf?#|WtFb7(zRtv%Gaz$^>?gTxuWEuvO5{o*Dw?|pduk33AKpWiT64@Q>e%DuMtK^ z;-m0P`C=l^hDg{a60Rv*UAl6`q)Dd2Idf*snPkdazPhYr$)hH`T%oihnnjYB=9E2H zzGiJ1wb+zjke`*8KhuP`@{;AIC9BIHDO>$x(nw)KN%``!C8o72O{FMxZJBAUSoR-T z%N{8&Et_OYS@L7{xeu3?maSQ{^x@^pA2qFxR7(ZjCVQl2%-i`)jZ2TqfXj%h_m`-e zpS7gyk*u|AADvstLcOp5EmX#i-kll+`(5cwKNH~?T&vO`x17rKf5$Zx_rJ%x6oi?$ z$|Be6nM^-uH1gp37}x!{%5hP7KS$hKHl{y-=ht!lJe%p)<2iF2?jI_92vh4LN=Lu3 zxM-}4anV?>z(r&ID_o$XvlnsEock1)7FPxm)7Z~PVydhTiJ}nFgrGU#!~>1}vHpM& z5V}(sqp_z7Vkty{;BGMXE$THQ{D@;J3afd>Q;34p2u*vz!=UHS^-N2lF_!5ND)eG{ z-rkQzA#|RHq%T5ubrOp~xF=-nMM+N_X{W7@M4B>NuR_P4zd;bC1Uu3D?%Y+CuLr?x#O`zn$Rz$nUP7G`cl%{}tlzLi}v(8{bCmDN2bp Vu{pTCm0x*hrguiY^3u)N{{t$l>Tv)7 literal 0 HcmV?d00001 diff --git a/boards/xc-fly/xc-slam/firmware.prototype b/boards/xc-fly/xc-slam/firmware.prototype new file mode 100644 index 0000000000..9d3f72a26b --- /dev/null +++ b/boards/xc-fly/xc-slam/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 319, + "magic": "PX4FWv1", + "description": "Firmware for the XC-FLY board", + "image": "", + "build_time": 0, + "summary": "XC-FLY", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1835008, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/xc-fly/xc-slam/init/rc.board_defaults b/boards/xc-fly/xc-slam/init/rc.board_defaults new file mode 100644 index 0000000000..828c3f01ba --- /dev/null +++ b/boards/xc-fly/xc-slam/init/rc.board_defaults @@ -0,0 +1,26 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ +param set-default BAT1_A_PER_V 17 +param set-default BAT1_N_CELLS 4 +param set-default BAT1_V_CHARGED 4.2 +param set-default BAT1_V_DIV 10.1 +param set-default BAT1_V_EMPTY 3.2 + +param set-default SYS_HAS_MAG 1 +param set-default PWM_MAIN_TIM0 -4 +param set-default RC_INPUT_PROTO -1 + +param set-default IMU_GYRO_RATEMAX 2000 +param set-default SYS_AUTOSTART 4001 +param set-default MC_PITCHRATE_K 0.4 +param set-default MC_ROLLRATE_K 0.35 +param set-default MC_YAWRATE_K 1.2 +param set-default MC_YAWRATE_MAX 360 +param set-default MAV_TYPE 2 +param set-default CA_AIRFRAME 0 +param set-default CA_ROTOR_COUNT 4 +param set-default CBRK_SUPPLY_CHK 894281 + +param set-default USB_MAV_MODE 5 diff --git a/boards/xc-fly/xc-slam/init/rc.board_extras b/boards/xc-fly/xc-slam/init/rc.board_extras new file mode 100644 index 0000000000..a6f12267a3 --- /dev/null +++ b/boards/xc-fly/xc-slam/init/rc.board_extras @@ -0,0 +1,7 @@ +#!/bin/sh +# +# board specific extras init +#------------------------------------------------------------------------------ + +# DShot telemetry is always on UART7 +# dshot telemetry -d /dev/ttyS5 diff --git a/boards/xc-fly/xc-slam/init/rc.board_sensors b/boards/xc-fly/xc-slam/init/rc.board_sensors new file mode 100644 index 0000000000..4f27cd2cf3 --- /dev/null +++ b/boards/xc-fly/xc-slam/init/rc.board_sensors @@ -0,0 +1,20 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ + +board_adc start +# heater start + +# BMI088 +bmi088 -A -R 2 -s start +bmi088 -G -R 2 -s start + +# 42688P +icm42688p -s start + +# baro +dps310 -I start -a 119 + +# internal mag +ist8310 -I -R 2 start diff --git a/boards/xc-fly/xc-slam/nuttx-config/Kconfig b/boards/xc-fly/xc-slam/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/xc-fly/xc-slam/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/xc-fly/xc-slam/nuttx-config/bootloader/defconfig b/boards/xc-fly/xc-slam/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..d3186f6ac1 --- /dev/null +++ b/boards/xc-fly/xc-slam/nuttx-config/bootloader/defconfig @@ -0,0 +1,90 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/xc-fly/xc-slam/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="XC-FLY XC-SLAM Bootloader" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="XC-FLY" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_USART6=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_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/xc-fly/xc-slam/nuttx-config/include/board.h b/boards/xc-fly/xc-slam/nuttx-config/include/board.h new file mode 100644 index 0000000000..e9546956be --- /dev/null +++ b/boards/xc-fly/xc-slam/nuttx-config/include/board.h @@ -0,0 +1,491 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6u/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The MatekH743-Slim board provides the following clock sources: + * + * X1: 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 8000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 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 = (8,000,000 / 1) * 120 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 clock source */ + +// #define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 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 board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED, + * that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PBA10 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */ +#define GPIO_USART1_CK GPIO_USART1_CK /* PB8 NC */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_CK GPIO_USART2_CK_2 /* PD7 NC */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ +#define GPIO_USART3_CK GPIO_USART3_CK_3 /* PD10 NC */ + +#define GPIO_UART4_RX GPIO_UART4_RX_3 /* PB8 */ +#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */ +#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 NC */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + + +/* SPI + * + + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */ +#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_2) /* PE2 */ + +/* I2C + * + + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_1 /* PD12 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_1 /* PD13 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN12) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN13) + +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ + +/* SDMMC1 + * + * SDMMC1_D0 PC8 + * SDMMC1_D1 PC9 + * SDMMC1_D2 PC10 + * SDMMC1_D3 PC11 + * SDMMC1_CK PC12 + * SDMMC1_CMD PD2 + */ + +// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */ +// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */ +// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */ +// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */ +// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */ +// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +// #if defined(CONFIG_BOARD_USE_PROBES) +// # include "stm32_gpio.h" +// # define PROBE_N(n) (1<<((n)-1)) +// # define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +// # define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +// # define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +// # define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +// # define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +// # define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +// # define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +// # define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +// # define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +// # define PROBE_INIT(mask) \ +// do { \ +// if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ +// if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ +// if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ +// if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ +// if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ +// if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ +// if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ +// if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ +// if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ +// } while(0) + +// # define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +// # define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +// #else +// # define PROBE_INIT(mask) +// # define PROBE(n,s) +// # define PROBE_MARK(n) +// #endif + +#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */ diff --git a/boards/xc-fly/xc-slam/nuttx-config/include/board_dma_map.h b/boards/xc-fly/xc-slam/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..a27735b354 --- /dev/null +++ b/boards/xc-fly/xc-slam/nuttx-config/include/board_dma_map.h @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once +// #define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +// #define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */ + +// DMAMUX2 +// #define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* DMA1:61 */ +// #define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* DMA1:62 */ + +// #define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */ +// #define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */ + +//TODO: UART DMA test +// #define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_1 /*DMA2:41*/ +// #define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_1 /*DMA2:42*/ + +// #define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */ +// #define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */ + +// #define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* DMA2:45 */ +// #define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* DMA2:46 */ + +#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA1:63 */ +#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA1:64 */ + +// #define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_0 /* DMA1:65 */ +// #define DMAMAP_UART5_TX DMAMAP_DMA12_UART5RX_0 /* DMA1:66 */ diff --git a/boards/xc-fly/xc-slam/nuttx-config/nsh/defconfig b/boards/xc-fly/xc-slam/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..64dc7a4b0c --- /dev/null +++ b/boards/xc-fly/xc-slam/nuttx-config/nsh/defconfig @@ -0,0 +1,268 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PRINTF is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/xc-fly/xc-slam/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="X-MAV AP-H743v2" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="X-MAV" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_IOB=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_MTD_W25=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_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_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_ADC2=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_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM2=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=921600 +CONFIG_UART4_RXBUFSIZE=3000 +CONFIG_UART4_RXDMA=y +CONFIG_UART4_TXBUFSIZE=3000 +CONFIG_UART4_TXDMA=y +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=3000 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=180 +CONFIG_USART6_SERIAL_CONSOLE=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y +CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/xc-fly/xc-slam/nuttx-config/scripts/bootloader_script.ld b/boards/xc-fly/xc-slam/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..fb877cc443 --- /dev/null +++ b/boards/xc-fly/xc-slam/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Durandal has a Switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/xc-fly/xc-slam/nuttx-config/scripts/script.ld b/boards/xc-fly/xc-slam/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..1dc1a0ef97 --- /dev/null +++ b/boards/xc-fly/xc-slam/nuttx-config/scripts/script.ld @@ -0,0 +1,228 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 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 board uses an STM32H743II and 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 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/xc-fly/xc-slam/src/CMakeLists.txt b/boards/xc-fly/xc-slam/src/CMakeLists.txt new file mode 100644 index 0000000000..798c524347 --- /dev/null +++ b/boards/xc-fly/xc-slam/src/CMakeLists.txt @@ -0,0 +1,69 @@ +############################################################################ +# +# Copyright (c) 2021 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + mtd.cpp + ) + # 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 + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/xc-fly/xc-slam/src/board_config.h b/boards/xc-fly/xc-slam/src/board_config.h new file mode 100644 index 0000000000..e5f6084ee9 --- /dev/null +++ b/boards/xc-fly/xc-slam/src/board_config.h @@ -0,0 +1,234 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#define FLASH_BASED_PARAMS + + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +# define GPIO_nLED_RED /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN15) +# define GPIO_nLED_GREEN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11) +# define GPIO_nLED_BLUE /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +#define ADC12_CH(n) (n) + +#define PX4_ADC_GPIO \ + /* PC4 */ GPIO_ADC12_INP4, \ + /* PC5 */ GPIO_ADC12_INP8 + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL ADC12_CH(4) +#define ADC_BATTERY_CURRENT_CHANNEL ADC12_CH(8) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL)) + +#define BOARD_ADC_OPEN_CIRCUIT_V (1.6f) + + + +/* Define Battery 1 Voltage Divider and A per V + */ + +// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +// #define BOARD_BATTERY1_A_PER_V (40.0f) +// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + + + + +// /* HEATER PA15 TIM2_CH1 +// * PWM in future +// */ +// #define GPIO_HEATER_OUTPUT /* PA15 T2CH1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +// #define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + + + + +/* Spare GPIO */ +#define GPIO_PA4 /* PA4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN4) +#define GPIO_PC0 /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0) +#define GPIO_PC1 /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1) +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 2 /* Timer 2*/ +#define TONE_ALARM_CHANNEL 1 /* PA15 GPIO_TIM2_CH1 NC */ +/*NC can be modified with Spare GPIO then connected with hardware */ +#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_BUZZER_1 +#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15) + +/* USB OTG FS + * + * PE15 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PE15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN15) +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */ + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS4" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +// #define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) +// #define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true); + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_LIB_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + GPIO_CAN1_TX,\ + GPIO_CAN1_RX, \ + PX4_ADC_GPIO, \ + GPIO_PC0, \ + GPIO_PC1, \ + GPIO_TONE_ALARM_IDLE, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 5 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/xc-fly/xc-slam/src/bootloader_main.c b/boards/xc-fly/xc-slam/src/bootloader_main.c new file mode 100644 index 0000000000..5670308a29 --- /dev/null +++ b/boards/xc-fly/xc-slam/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/xc-fly/xc-slam/src/flash_w25q128.c b/boards/xc-fly/xc-slam/src/flash_w25q128.c new file mode 100644 index 0000000000..3a3e2cee1f --- /dev/null +++ b/boards/xc-fly/xc-slam/src/flash_w25q128.c @@ -0,0 +1,505 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file flash_w25q128.c + * + * Board-specific external flash W25Q128 functions. + */ + + +#include "board_config.h" +#include "qspi.h" +#include "arm_internal.h" +#include +#include + + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#define N25Q128_SECTOR_SIZE (4*1024) +#define N25Q128_SECTOR_SHIFT (12) +#define N25Q128_SECTOR_COUNT (4096) +#define N25Q128_PAGE_SIZE (256) +#define N25Q128_PAGE_SHIFT (8) + +#define W25Q_DUMMY_CYCLES_FAST_READ_QUAD 6 +#define W25Q_INSTR_FAST_READ_QUAD 0xEB +#define W25Q_ADDRESS_SIZE 3 // 3 bytes -> 24 bits + +#define N25QXXX_READ_STATUS 0x05 /* Read status register: * + * 0x05 | SR */ +#define N25QXXX_PAGE_PROGRAM 0x02 /* Page Program: * + * 0x02 | ADDR(MS) | ADDR(MID) | * + * ADDR(LS) | data */ +#define N25QXXX_WRITE_ENABLE 0x06 /* Write enable: * + * 0x06 */ +#define N25QXXX_WRITE_DISABLE 0x04 /* Write disable command code: * + * 0x04 */ +#define N25QXXX_SUBSECTOR_ERASE 0x20 /* Sub-sector Erase (4 kB) * + * 0x20 | ADDR(MS) | ADDR(MID) | * + * ADDR(LS) */ + + +/* N25QXXX Registers ****************************************************************/ +/* Status register bit definitions */ + +#define STATUS_BUSY_MASK (1 << 0) /* Bit 0: Device ready/busy status */ +# define STATUS_READY (0 << 0) /* 0 = Not Busy */ +# define STATUS_BUSY (1 << 0) /* 1 = Busy */ +#define STATUS_WEL_MASK (1 << 1) /* Bit 1: Write enable latch status */ +# define STATUS_WEL_DISABLED (0 << 1) /* 0 = Not Write Enabled */ +# define STATUS_WEL_ENABLED (1 << 1) /* 1 = Write Enabled */ +#define STATUS_BP_SHIFT (2) /* Bits 2-4: Block protect bits */ +#define STATUS_BP_MASK (7 << STATUS_BP_SHIFT) +# define STATUS_BP_NONE (0 << STATUS_BP_SHIFT) +# define STATUS_BP_ALL (7 << STATUS_BP_SHIFT) +#define STATUS_TB_MASK (1 << 5) /* Bit 5: Top / Bottom Protect */ +# define STATUS_TB_TOP (0 << 5) /* 0 = BP2-BP0 protect Top down */ +# define STATUS_TB_BOTTOM (1 << 5) /* 1 = BP2-BP0 protect Bottom up */ +#define STATUS_BP3_MASK (1 << 5) /* Bit 6: BP3 */ +#define STATUS_SRP0_MASK (1 << 7) /* Bit 7: Status register protect 0 */ +# define STATUS_SRP0_UNLOCKED (0 << 7) /* 0 = WP# no effect / PS Lock Down */ +# define STATUS_SRP0_LOCKED (1 << 7) /* 1 = WP# protect / OTP Lock Down */ + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/* This type represents the state of the MTD device. The struct mtd_dev_s must + * appear at the beginning of the definition so that you can freely cast between + * pointers to struct mtd_dev_s and struct n25qxxx_dev_s. + */ + +struct n25qxxx_dev_s { + //struct mtd_dev_s mtd; /* MTD interface */ + FAR struct qspi_dev_s *qspi; /* Saved QuadSPI interface instance */ + uint16_t nsectors; /* Number of erase sectors */ + uint8_t sectorshift; /* Log2 of sector size */ + uint8_t pageshift; /* Log2 of page size */ + FAR uint8_t *cmdbuf; /* Allocated command buffer */ + FAR uint8_t *readbuf; /* Allocated status read buffer */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct qspi_dev_s *ptr_qspi_dev; +struct qspi_meminfo_s qspi_meminfo = { + .flags = QSPIMEM_QUADIO, + .addrlen = W25Q_ADDRESS_SIZE, + .dummies = W25Q_DUMMY_CYCLES_FAST_READ_QUAD, + .cmd = W25Q_INSTR_FAST_READ_QUAD +}; + +struct n25qxxx_dev_s n25qxxx_dev; +uint8_t cmdbuf[4] = {0u}; +uint8_t readbuf[1] = {0u}; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ +__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd); +__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv); +__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd, + FAR void *buffer, size_t buflen); +__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv); +__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv); + +__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer, + off_t address, size_t buflen); + +__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo); + +__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector); + +__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status, + off_t address); + +__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd, + off_t addr, uint8_t addrlen); + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +void flash_w25q128_init(void) +{ + int qspi_interface_number = 0; + ptr_qspi_dev = stm32h7_qspi_initialize(qspi_interface_number); + n25qxxx_dev.qspi = ptr_qspi_dev; + n25qxxx_dev.cmdbuf = cmdbuf; + n25qxxx_dev.readbuf = readbuf; + n25qxxx_dev.sectorshift = N25Q128_SECTOR_SHIFT; + n25qxxx_dev.pageshift = N25Q128_PAGE_SHIFT; + n25qxxx_dev.nsectors = N25Q128_SECTOR_COUNT; +} + +__ramfunc__ ssize_t up_progmem_ext_getpage(size_t addr) +{ + ssize_t page_address = (addr - STM32_FMC_BANK4) / N25Q128_SECTOR_COUNT; + + return page_address; +} + +__ramfunc__ ssize_t up_progmem_ext_eraseblock(size_t block) +{ + ssize_t size = N25Q128_SECTOR_COUNT; + + irqstate_t irqstate = px4_enter_critical_section(); + stm32h7_qspi_exit_memorymapped(ptr_qspi_dev); + + n25qxxx_erase_sector(&n25qxxx_dev, block); + + stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0); + px4_leave_critical_section(irqstate); + return size; +} + +__ramfunc__ ssize_t up_progmem_ext_write(size_t addr, FAR const void *buf, size_t count) +{ + ssize_t ret_val = 0; + + irqstate_t irqstate = px4_enter_critical_section(); + stm32h7_qspi_exit_memorymapped(ptr_qspi_dev); + + addr &= 0xFFFFFF; + n25qxxx_write_page(&n25qxxx_dev, buf, (off_t)addr, count); + + stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0); + px4_leave_critical_section(irqstate); + + return ret_val; +} + +/************************************************************************************ + * Name: n25qxxx_command + ************************************************************************************/ + +__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd) +{ + struct qspi_cmdinfo_s cmdinfo; + + finfo("CMD: %02" PRIx8 "\n", cmd); + + cmdinfo.flags = 0; + cmdinfo.addrlen = 0; + cmdinfo.cmd = cmd; + cmdinfo.buflen = 0; + cmdinfo.addr = 0; + cmdinfo.buffer = NULL; + + int rv; + rv = qspi_command(qspi, &cmdinfo); + return rv; +} + +/************************************************************************************ + * Name: n25qxxx_read_status + ************************************************************************************/ + +__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv) +{ + DEBUGVERIFY(n25qxxx_command_read(priv->qspi, N25QXXX_READ_STATUS, + (FAR void *)&priv->readbuf[0], 1)); + return priv->readbuf[0]; +} + +/************************************************************************************ + * Name: n25qxxx_command_read + ************************************************************************************/ + +__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd, + FAR void *buffer, size_t buflen) +{ + struct qspi_cmdinfo_s cmdinfo; + + finfo("CMD: %02" PRIx8 " buflen: %zu\n", cmd, buflen); + + cmdinfo.flags = QSPICMD_READDATA; + cmdinfo.addrlen = 0; + cmdinfo.cmd = cmd; + cmdinfo.buflen = buflen; + cmdinfo.addr = 0; + cmdinfo.buffer = buffer; + + int rv; + rv = qspi_command(qspi, &cmdinfo); + return rv; +} + + +/************************************************************************************ + * Name: n25qxxx_write_enable + ************************************************************************************/ + +__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv) +{ + uint8_t status; + + do { + n25qxxx_command(priv->qspi, N25QXXX_WRITE_ENABLE); + status = n25qxxx_read_status(priv); + } while ((status & STATUS_WEL_MASK) != STATUS_WEL_ENABLED); +} + +/************************************************************************************ + * Name: n25qxxx_write_disable + ************************************************************************************/ + +__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv) +{ + uint8_t status; + + do { + n25qxxx_command(priv->qspi, N25QXXX_WRITE_DISABLE); + status = n25qxxx_read_status(priv); + } while ((status & STATUS_WEL_MASK) != STATUS_WEL_DISABLED); +} + +/************************************************************************************ + * Name: n25qxxx_write_page + ************************************************************************************/ + +__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer, + off_t address, size_t buflen) +{ + struct qspi_meminfo_s meminfo; + unsigned int pagesize; + unsigned int npages; + unsigned int firstpagesize = 0; + int ret = OK; + unsigned int i; + + finfo("address: %08jx buflen: %zu\n", (intmax_t)address, buflen); + + pagesize = (1 << priv->pageshift); + + /* Set up non-varying parts of transfer description */ + + meminfo.flags = QSPIMEM_WRITE; + meminfo.cmd = N25QXXX_PAGE_PROGRAM; + meminfo.addrlen = 3; + meminfo.dummies = 0; + meminfo.buffer = (void *)buffer; + + if (0 != (address % pagesize)) { + firstpagesize = pagesize - (address % pagesize); + } + + if (buflen <= firstpagesize) { + meminfo.addr = address; + meminfo.buflen = buflen; + ret = n25qxxx_write_one_page(priv, &meminfo); + + } else { + + if (firstpagesize > 0) { + meminfo.addr = address; + meminfo.buflen = firstpagesize; + ret = n25qxxx_write_one_page(priv, &meminfo); + + buffer += firstpagesize; + address += firstpagesize; + buflen -= firstpagesize; + } + + npages = (buflen >> priv->pageshift); + + meminfo.buflen = pagesize; + + /* Then write each page */ + + for (i = 0; (i < npages) && (ret == OK); i++) { + /* Set up varying parts of the transfer description */ + + meminfo.addr = address; + meminfo.buffer = (void *)buffer; + + ret = n25qxxx_write_one_page(priv, &meminfo); + + /* Update for the next time through the loop */ + + buffer += pagesize; + address += pagesize; + buflen -= pagesize; + } + + if ((ret == OK) && (buflen > 0)) { + meminfo.addr = address; + meminfo.buffer = (void *)buffer; + meminfo.buflen = buflen; + + ret = n25qxxx_write_one_page(priv, &meminfo); + } + } + + return ret; +} + +__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo) +{ + int ret; + + n25qxxx_write_enable(priv); + ret = qspi_memory(priv->qspi, meminfo); + n25qxxx_write_disable(priv); + + if (ret < 0) { + ferr("ERROR: QSPI_MEMORY failed writing address=%06" PRIx32 "\n", + meminfo->addr); + } + + return ret; +} + +/************************************************************************************ + * Name: n25qxxx_erase_sector + ************************************************************************************/ + +__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector) +{ + off_t address; + uint8_t status; + + finfo("sector: %08jx\n", (intmax_t) sector); + + /* Check that the flash is ready and unprotected */ + + status = n25qxxx_read_status(priv); + + if ((status & STATUS_BUSY_MASK) != STATUS_READY) { + ferr("ERROR: Flash busy: %02" PRIx8, status); + return -EBUSY; + } + + /* Get the address associated with the sector */ + + address = (off_t)sector << priv->sectorshift; + + if ((status & (STATUS_BP3_MASK | STATUS_BP_MASK)) != 0 && + n25qxxx_isprotected(priv, status, address)) { + ferr("ERROR: Flash protected: %02" PRIx8, status); + return -EACCES; + } + + /* Send the sector erase command */ + + n25qxxx_write_enable(priv); + n25qxxx_command_address(priv->qspi, N25QXXX_SUBSECTOR_ERASE, address, 3); + + /* Wait for erasure to finish */ + + while ((n25qxxx_read_status(priv) & STATUS_BUSY_MASK) != 0); + + return OK; +} + +/************************************************************************************ + * Name: n25qxxx_isprotected + ************************************************************************************/ + +__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status, + off_t address) +{ + off_t protstart; + off_t protend; + off_t protsize; + unsigned int bp; + + /* The BP field is spread across non-contiguous bits */ + + bp = (status & STATUS_BP_MASK) >> STATUS_BP_SHIFT; + + if (status & STATUS_BP3_MASK) { + bp |= 8; + } + + /* the BP field is essentially the power-of-two of the number of 64k sectors, + * saturated to the device size. + */ + + if (0 == bp) { + return false; + } + + protsize = 0x00010000; + protsize <<= (protsize << (bp - 1)); + protend = (1 << priv->sectorshift) * priv->nsectors; + + if (protsize > protend) { + protsize = protend; + } + + /* The final protection range then depends on if the protection region is + * configured top-down or bottom up (assuming CMP=0). + */ + + if ((status & STATUS_TB_MASK) != 0) { + protstart = 0x00000000; + protend = protstart + protsize; + + } else { + protstart = protend - protsize; + /* protend already computed above */ + } + + return (address >= protstart && address < protend); +} + +/************************************************************************************ + * Name: n25qxxx_command_address + ************************************************************************************/ + +__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd, + off_t addr, uint8_t addrlen) +{ + struct qspi_cmdinfo_s cmdinfo; + + finfo("CMD: %02" PRIx8 " Address: %04jx addrlen=%" PRIx8 "\n", cmd, (intmax_t) addr, addrlen); + + cmdinfo.flags = QSPICMD_ADDRESS; + cmdinfo.addrlen = addrlen; + cmdinfo.cmd = cmd; + cmdinfo.buflen = 0; + cmdinfo.addr = addr; + cmdinfo.buffer = NULL; + + int rv; + rv = qspi_command(qspi, &cmdinfo); + return rv; +} diff --git a/boards/xc-fly/xc-slam/src/hw_config.h b/boards/xc-fly/xc-slam/src/hw_config.h new file mode 100644 index 0000000000..e986fe0e90 --- /dev/null +++ b/boards/xc-fly/xc-slam/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 6 +#define INTERFACE_USART_CONFIG "/dev/ttyS5,57600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 319 +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (16 * 128 * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_RED // RED +#define BOARD_LED_ON 1 +#define BOARD_LED_OFF 0 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/xc-fly/xc-slam/src/i2c.cpp b/boards/xc-fly/xc-slam/src/i2c.cpp new file mode 100644 index 0000000000..d557e692af --- /dev/null +++ b/boards/xc-fly/xc-slam/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusInternal(1), + initI2CBusExternal(4), +}; diff --git a/boards/xc-fly/xc-slam/src/init.c b/boards/xc-fly/xc-slam/src/init.c new file mode 100644 index 0000000000..cd7d3d2162 --- /dev/null +++ b/boards/xc-fly/xc-slam/src/init.c @@ -0,0 +1,210 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + UNUSED(ms); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* configure USB interfaces */ + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + return ret; + } + +#endif + +// TODO:internal flash store parameters +#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_RED); + } + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/xc-fly/xc-slam/src/led.c b/boards/xc-fly/xc-slam/src/led.c new file mode 100644 index 0000000000..0420c1da2e --- /dev/null +++ b/boards/xc-fly/xc-slam/src/led.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/xc-fly/xc-slam/src/manifest.c b/boards/xc-fly/xc-slam/src/manifest.c new file mode 100644 index 0000000000..ab9c952cdd --- /dev/null +++ b/boards/xc-fly/xc-slam/src/manifest.c @@ -0,0 +1,131 @@ +/**************************************************************************** + * + * Copyright (c) 2018-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file manifest.c + * + * This module supplies the interface to the manifest of hardware that is + * optional and dependent on the HW REV and HW VER IDs + * + * The manifest allows the system to know whether a hardware option + * say for example the PX4IO is an no-pop option vs it is broken. + * + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#include "systemlib/px4_macros.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +typedef struct { + uint32_t hw_ver_rev; /* the version and revision */ + const px4_hw_mft_item_t *mft; /* The first entry */ + uint32_t entries; /* the length of the list */ +} px4_hw_mft_list_entry_t; + +typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry; +#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1 + +static const px4_hw_mft_item_t device_unsupported = {0, 0, 0}; + +// List of components on a specific board configuration +// The index of those components is given by the enum (px4_hw_mft_item_id_t) +// declared in board_common.h +static const px4_hw_mft_item_t hw_mft_list_v0600[] = { + { + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, +}; + +static px4_hw_mft_list_entry_t mft_lists[] = { + {V6U00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, +}; + +/************************************************************************************ + * Name: board_query_manifest + * + * Description: + * Optional returns manifest item. + * + * Input Parameters: + * manifest_id - the ID for the manifest item to retrieve + * + * Returned Value: + * 0 - item is not in manifest => assume legacy operations + * pointer to a manifest item + * + ************************************************************************************/ + +__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id) +{ + static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized; + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + uint32_t ver_rev = board_get_hw_version() << 16; + ver_rev |= board_get_hw_revision(); + + for (unsigned i = 0; i < arraySize(mft_lists); i++) { + if (mft_lists[i].hw_ver_rev == ver_rev) { + boards_manifest = &mft_lists[i]; + break; + } + } + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev); + } + } + + px4_hw_mft_item rv = &device_unsupported; + + if (boards_manifest != px4_hw_mft_list_uninitialized && + id < boards_manifest->entries) { + rv = &boards_manifest->mft[id]; + } + + return rv; +} diff --git a/boards/xc-fly/xc-slam/src/mtd.cpp b/boards/xc-fly/xc-slam/src/mtd.cpp new file mode 100644 index 0000000000..e89e53e03b --- /dev/null +++ b/boards/xc-fly/xc-slam/src/mtd.cpp @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +//TODO:Prepare for NxtDual + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi2 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(2) // SPIDEV_FLASH(0) +}; + +static const px4_mtd_entry_t fmum_flash = { + .device = &spi2, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = 32 + + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 1, + .entries = { + &fmum_flash + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mtd_mft + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/xc-fly/xc-slam/src/sdio.c b/boards/xc-fly/xc-slam/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/xc-fly/xc-slam/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/xc-fly/xc-slam/src/spi.cpp b/boards/xc-fly/xc-slam/src/spi.cpp new file mode 100644 index 0000000000..afaacd4eef --- /dev/null +++ b/boards/xc-fly/xc-slam/src/spi.cpp @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin3}, SPI::DRDY{GPIO::PortA, GPIO::Pin1}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin2}, SPI::DRDY{GPIO::PortA, GPIO::Pin0}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(2), SPI::CS{GPIO::PortD, GPIO::Pin4}) + }), + initSPIBus(SPI::Bus::SPI3, { + //initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortA, GPIO::Pin15}) + }), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin13}, SPI::DRDY{GPIO::PortE, GPIO::Pin4}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/xc-fly/xc-slam/src/timer_config.cpp b/boards/xc-fly/xc-slam/src/timer_config.cpp new file mode 100644 index 0000000000..a1e8d8672b --- /dev/null +++ b/boards/xc-fly/xc-slam/src/timer_config.cpp @@ -0,0 +1,61 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * + * * TIM2_CH1 T HEATER > PWM OUT or GPIO PA15 + ****************************************************************************/ + + +#include + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer2, DMA{DMA::Index1}), + initIOTimer(Timer::Timer3, DMA{DMA::Index1}), + // initIOTimer(Timer::Timer2), + // initIOTimer(Timer::Timer3), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}), + + +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/xc-fly/xc-slam/src/usb.c b/boards/xc-fly/xc-slam/src/usb.c new file mode 100644 index 0000000000..9591784866 --- /dev/null +++ b/boards/xc-fly/xc-slam/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_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); +}