From f8a42bcd5830777886e4ff088fb912f78495c87d Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Mon, 3 Jun 2024 13:06:47 +0800 Subject: [PATCH] boards: add new board micoair h743 --- boards/micoair/h743/bootloader.px4board | 3 + boards/micoair/h743/default.px4board | 85 ++++ .../h743/extras/micoair_h743_bootloader.bin | Bin 0 -> 41020 bytes boards/micoair/h743/firmware.prototype | 13 + boards/micoair/h743/init/rc.board_defaults | 24 + boards/micoair/h743/init/rc.board_extras | 7 + boards/micoair/h743/init/rc.board_sensors | 18 + .../h743/nuttx-config/bootloader/defconfig | 89 ++++ .../micoair/h743/nuttx-config/include/board.h | 426 ++++++++++++++++++ .../h743/nuttx-config/include/board_dma_map.h | 36 ++ .../micoair/h743/nuttx-config/nsh/defconfig | 245 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 +++++++++ .../h743/nuttx-config/scripts/script.ld | 228 ++++++++++ boards/micoair/h743/src/CMakeLists.txt | 68 +++ boards/micoair/h743/src/board_config.h | 197 ++++++++ boards/micoair/h743/src/bootloader_main.c | 75 +++ boards/micoair/h743/src/hw_config.h | 135 ++++++ boards/micoair/h743/src/i2c.cpp | 39 ++ boards/micoair/h743/src/init.c | 203 +++++++++ boards/micoair/h743/src/led.c | 114 +++++ boards/micoair/h743/src/sdio.c | 177 ++++++++ boards/micoair/h743/src/spi.cpp | 50 ++ boards/micoair/h743/src/timer_config.cpp | 56 +++ boards/micoair/h743/src/usb.c | 78 ++++ 24 files changed, 2579 insertions(+) create mode 100644 boards/micoair/h743/bootloader.px4board create mode 100644 boards/micoair/h743/default.px4board create mode 100644 boards/micoair/h743/extras/micoair_h743_bootloader.bin create mode 100644 boards/micoair/h743/firmware.prototype create mode 100644 boards/micoair/h743/init/rc.board_defaults create mode 100644 boards/micoair/h743/init/rc.board_extras create mode 100644 boards/micoair/h743/init/rc.board_sensors create mode 100644 boards/micoair/h743/nuttx-config/bootloader/defconfig create mode 100644 boards/micoair/h743/nuttx-config/include/board.h create mode 100644 boards/micoair/h743/nuttx-config/include/board_dma_map.h create mode 100644 boards/micoair/h743/nuttx-config/nsh/defconfig create mode 100644 boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/micoair/h743/nuttx-config/scripts/script.ld create mode 100644 boards/micoair/h743/src/CMakeLists.txt create mode 100644 boards/micoair/h743/src/board_config.h create mode 100644 boards/micoair/h743/src/bootloader_main.c create mode 100644 boards/micoair/h743/src/hw_config.h create mode 100644 boards/micoair/h743/src/i2c.cpp create mode 100644 boards/micoair/h743/src/init.c create mode 100644 boards/micoair/h743/src/led.c create mode 100644 boards/micoair/h743/src/sdio.c create mode 100644 boards/micoair/h743/src/spi.cpp create mode 100644 boards/micoair/h743/src/timer_config.cpp create mode 100644 boards/micoair/h743/src/usb.c diff --git a/boards/micoair/h743/bootloader.px4board b/boards/micoair/h743/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/micoair/h743/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/micoair/h743/default.px4board b/boards/micoair/h743/default.px4board new file mode 100644 index 0000000000..98d8f08aaf --- /dev/null +++ b/boards/micoair/h743/default.px4board @@ -0,0 +1,85 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_URT6="/dev/ttyS5" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_BOSCH_BMI270=y +CONFIG_COMMON_INS=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_ATXXXX=y +CONFIG_DRIVERS_PPS_CAPTURE=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_TAP_ESC=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_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_PAYLOAD_DELIVERER=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_FAILURE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=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_SERIAL_PASSTHRU=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/micoair/h743/extras/micoair_h743_bootloader.bin b/boards/micoair/h743/extras/micoair_h743_bootloader.bin new file mode 100644 index 0000000000000000000000000000000000000000..ca8c511279669e21033c2c92bded52ffc0e6e2d3 GIT binary patch literal 41020 zcmeFZdwdkt89#jHvb&QDWOG55B*0#RZn8lZf*8chvb#(!i-wD~T&ykxaUu#4P*Evt z2x+@A)mqzKAZ;KZ5s-ldb(REna^3fPc8P5*ec#XTzxR*d zem=8jX3lf&&-0w;c4k5v$TmAZtHKQ-~mXwL7RcnAKk95~u=q-um)?CuB zci3t9#719-Q0420tE%ist|~9s$dN3eZiHt<;fc(TMx>;h6^`BJtZF1?Vj{|KdWU(^ z|10N)BBDIoLzE$1L@DVe%41!P9VNeN>{#-v5~bC0RNXkntT5~$q({{)*Y3BB8Gs?m z{$8T!Q10_y(pZ>GvNjTu^&&0|IjiP1B0N^SrsjxB##=gl7FVY)?_=DTd6>;iHL;P7 zLq3{1IvRYXo};QE%iLK$->f9DPDMbQhODD%Cf>EqcPb7%Xa4KC(>Fi%j510&;AuXE zH~!nRF>6}!A=R2yf`5DTKR=7TLdG3Z9a&THE*J15%c<;|aR@2B-^lbd(KH$9UFZ?X z+C=D^M5|NLqJ=~&dTDibI-F=NdcTqHX&Mhm-ue>mj;ftmB}&a?r@{idGb@NToS46l zqHP(hn*cMW*lbGn9#!?|sSZ8o0IAQipbmW&tK_qWoUY(e^w@JdcY#171PCLh~tnw7wLSPl?rs@`@u`maQo-pet0( z-E}2@H&e|_8Y7cN;$UZ~V_qUDMk9HO<#c0MhN%)72{Dox`nv3?#K@SBp_EHuxWh9DHjvpjg8mFjRQ`e=^Hb6CwCPhlwzP}sw&mnX_IY9y@mA5)uA2Puu!(+s$i z$Ulkn7}8@%TaoXZ=~7-pZLN5|fcF=WUP5{ase)8NdJgG1q@74R$LkwnV<0{<{o(KX z+X#s;8f~pq$DMeHF#%8$3gcvF7>7Ra~dIwhHeqy2d=W5pi`hcG|+CL!5J^QBnnTg-ZBjbYB##=BTAEn{zpTv}5@%$Y?sSDsm&&`iwE%Q@2*Sd(!VZ#CdwI6zmO z*~CVxrV{e&L3-Z6Y_U>x*-JUCpS2Hc~`KSH^@&Oxjipl@S z50LLIW5@t^pd5slfsf!FX`_LAz|FML1G(h|x7NkqohaI*g!)V|+skYu$`v(RVzv@x zZBJS~vE)iNuTkV`>{!b!(YZ^jbSXSn*^yQi<4)tjkti*WM+;SGp&YbSHJYw-l2uR7WcF3#oG-PUd^y!lPaxQzkM2Xn-4arkCM&F&0^&Z}u;N^lP;BKkjBeKTI;-2KG zvNn3>vvkNw*0VvKhqexUY2?2qtpct@TzXtt-y&_ryE-~5V-am(uEZ%x+?-4tXELe9v2iYNIaNMmGobYzV%8TW7}LE( zsqH4_!9|>rDDQQn7V{A`^A3x$+T~JOT_59Ku~6KZ|3{(0hdzOS3*;PWrStxE91;Au zQtNyc=It_(7bD@4h_OB?_tZr)mOVAh%hu={(j{{n!=`&xIkk@b05|D6aPh8mZIBkcQYZpW|&I3O9ION9EvWJV!4KR_ObID_LbG5nOMC81{eNkG`mkwC3nq{1?=b zJ8-=bva;5k@QKsvt6!J2ZA$p+LV_|~*>t+YREw9V5k(wxI=5$H;<` zHbY@q$H>BxwqZq&bc`%2X-h9&)G@NSq%FhqXvato?SDyI=2X=AMQqN#JVD39=lr^b z&euR&G<_q)v-{nTx?(piPuC57wG7k~TSuM+JraF95sbKmI!4*q!+=77 z6GowqC`6_Il|3ZK70@e85+_a!Ft>3klfmTVA6M!ow=tuBt9!537GQ6)sO(%W$8h|9 z-IO+sctc~_$TZQV@{7zO*Ul&Ea#EYm2ul>5PS?XaZ+CDx7Wdjl{x%B1`A4%NGdZ6Hhm|v}B&R1>UVz<1iQ7kvNKJysC_VMO^49*y zC8m&33igvmA(17N2i`uFvD|+5i)KDluCeTa;TLk z2UV?7)0OE-@Po#CGLUMOFCyvD=kf@nyx7Gki+gxwNI!3hE2JgTdo@byJ1HtF;dG76)nnggCv=gZE-Z8VFvh)p#-_n_p9$BBj))zsQVBUmL}%Mp_T$p{X8yUApwKKLv2_)KmH6$0Mrk zGTMnP?j*6Ku8jxO%=(y|M2z|dW>R%+>RMvE68v6fl-IgL@<6=~)L&lre2qqY(KuNA z@*+QuRi5tW#ekofKCR?lO5Dc2l(3C?DSq22vt7KC=>SM+e%P?U3mk}OoII>RnD!WDd>X#SE_*5}oWKEIq z!Dvou9e?dDF-OAf5xU}|FLo3>zq(4)h%bp_#gXDE)w+WyuXgbxZfili3a2GXGoBJ# zUhvNlCyG|k;A`Fd2n})}*CHqN#83V7{`Xy`)^XzWD8y%Y|J{jq77<%0FgE&TZ1*KO zp}I(nF9z%@L`hZo5ocNww@*ecQFh>|C0gUpyC^1t8@@mq2c;5W^u=%qFAf%&P1{7Q z$P53yYo1nnci{4!P{}l6Y*vY#xh20iS*mglYSBvvLA8ha#usZuVx1C<)V=`R!~Btn zt<30TX|iaYSmr@%{xhQh28NYVB`SyK%P28E;%p zcb$dH!AT~b-C$8lxl|V)aW!k_gI1&3jk`@lskPesCk{#lUk zFtT4Uw=nkiG>MNZLm@nVg;NMy!O z!_!IiUU&19j36-4@|bZ){AC%Z%YZ6{@f`5a5(cDr0|kk=FfN=M6`g@$M<1 z;1WekF3KL2FS$?UM}m{T#DVKnh|D&l7#CvVIOTnHsyhJOodBPOZr~J-V{L4}2#l%*2WE`uRdS0oN1CA;?VkFx8{RC7!3e=* zaaTbk{CqECuX27LWQ?lJ025i|*ZpdgZg~-!L*2Pr&SMe{pu6fGBQSrBN@-eOXE5=2 z0@w8Klv*SX61E=PECJlCybkl(`O9)vsp{p$jo|e=do&~XC?zlHwTk5pd?<_T^=g!s ze)Mw`t1OCiL@8R40~gtG>0ZV>XK8sse%)G0BaZi%KEv4fPpC>zih zDksvKG|BMI)?J`lS4iM$}1CdL_!WZ*JPBl-@kH zBH_V(k3LHI$+_NhF5bay$-)klhSD17RopJ3l&h{xM$`wGjodC)Y42mUQE2cY(e7u4 z)B9?Sizqj%9Beh;V8*WWGRD)_+R3l0lrV@(IgkX)fRX*)C)Kj>n zJ(uN3_}7t68FKREL1NqrUd-O(wzJATeT-EnuA=>?lEIJ0X<2=>R%=TMX0PBwh2YS) z_Idp_$ta$EXpv-DNGv-Sz~&H%$_Y2_ZKdh&r0f-_i()FBdss8*+*51D&aza$;pr-; z5Ij;#EgX6N9BGdC5ox=(RnCwU`6t+?d;Iqmg3@}8_4guuxR+Ru1Z`TneCq3CKc7T8U zsYi<)C^z7c3ilA@;~rx51eT!(wbB}Ihg7ZQk7ci5EE^oDu1c>>I)t8a^RC|}ADYV0 zR?qdAvA_Ilo+9DbdQhV3db6#y3Be!F?{E7b?5-OC2LS1Tni)bPNM7kfDDZoWA5 zHJ;fFEED#2neFUm^skb84eR&9(m$?4%P(O4&TQa*eY!RU*1q@v-ECRru^y(H^Rm^Y zYjx56a+;{wMC;USr*n8I@bw1GrpcY;@vkcc+-Nh23`$$zU-A!ux&TepZ zlG3x4dhkeaD#eIgI>SWSwU2VPe9+g)7`KL@%LnacM>E^$=a ztoUzEA78AOynbRE+!6;pg1If-F%1%#!T+(e-D$uYe-YicpsgCaWGa`@J(2Rz>#qQ} znxDkkV6{}{cJme;XsvWDQ6_iCRwchd2Vch3p0NDCq#&Xk_+huO`?;zNo;e22nsPV*9MtK6RMcJjM@Yrv2Y7wJ3p04 zP-ZRWgvtt_CdwJ3JNRl%PFzs)XigO~E~PfdN6eGgvf$v4UF%yuY_ux$NvkLO9JXE{y)V%eP)#N5sg^rCn2vc_X(?LxMeKxs=RBrGaU398Ref5UYtd9HSA48 z@44v-qi7gUAs*~{6A%tSe0mMSp&>Wv@40E2QPf8v?)d?t?gt3=CgI;8?ubID4Lh)h z?!r}rYk;@?ui58{D76{8D78`DnUGZP4F`zvvP^89!35YDLV-y5yFOz5Hh5m1D9!>+oa(cK3ozzSE)ok13Glp} z>o0|^c&D_;dsezCds)SR@y$H z+_@@NrV4k0_)$~_r}IfHx7MwZ7`k&j_hW5*OIdDxj8d4b)N*cmn%TuF9cq?z8FI@Y z*lr#ENSIf%%F_InmG3w?$a8}*5BUvQ(iJ&!DFwVdLvs0(G18x@t@ZlCm^}5mtihT7M<~_eIQPg=f;!Jg{o@+nMWjx)Y+tIoZ2IEr1|v+FOqSyyn;8iH3MrzpY+~BXitf) zvHMxDs258lClthU-bWV+VW3&jefQS7l)H1K+~`_m!(vI-I|=J%QK93dmWd@-6U*O& z?*9vwbuce;%EVp;B ztNAp-z>ao3NtexbD6jg`I?GEAcX0Nh0gJ9gNs99{LTBe(Vu_NKSfUsctI7SUwl%Js z>muD;$IWeVgI#Tdxv8qwUeZ<=$65ZNl2$I8>yASnH+V@Km&o9r!sK}u2l!4$9{O|F zq5yh%S7IY;At;g9O5qdR21o1a@cQbbZO0F^on6aTW2o9aHZePrYLuJM=><7trGcS#iG)hM=vyF#r6$$6}52E$?HA-Kv(RH|X zygwdR(HwvG!W`+yVpy1Klm?rm3q4AXFOKdqkeJ@wN9&`uN6MR^yDmzEl`mPWuBZC@ z*xp^GyB5{>nPC@7O^S|*OD`)W%3sv>4a5i!@67hf{07&eoz6=EqRdpOB~K2Xk*T-t zvK%*6sIyQ__&WAhjdG^XA~i3D&JeYgFd}>mb>uXas)RaS@j;8Oh?zuvc0EB2Y~R!$ zLuY|ep4m_1DZc;ky{`y<`E~JAM_~@0>$Up@jMeOKTWF4sHNU|kX`&--xR8%=j*X6! zj*-fYzC}j=*$pi`)5JjMf`txafo;xm_~PKa(o$+G(v7WL#ETfS=2^dM(L2t;#}6&a z5eX#2{%}RlnMItK<33Y5f6oiAGZOy1 z(Xr^5Ia}NjI>xmwGPqk8_J^-_pItO>(V4{w?o@AS*_p)_#6f(luC+sMSbBCbywJua z$_?z<#oOmAX8QcsX=fMDfmBZUr@qd$m>0PN8Cb(L&f&rIsTL`&U2GI%n&E%zM8skhOBY7MJNsj{ zCE%gRl)Y?a! ze#5Q6$AeP5=<{>ZUiASzdC4UHM&d)mxm^Xs%AK&Rq>&(&<#aDwqVVJ@WD=#0U*+DD zDlTA#lzcP$W`4-A_qo)23LB>=zK3phF|LRU=~>1SR5J@VJ1nk`)XaRP!6aJ5W55TJAUKHH5rNCw(OS1rH5^R4r=)G_ z(1zJIe(14xxMWYPEgLKmKeW~MB4Scv?H%}!_Q)#6qAjj;5F!81$ z%C%HiLPQI-JkiqB^5j_+2P`0|1~;|be6%vbb!d4^SJF4Ih;b5xgB^qDE`fRAR?h2~ z%yG-+`7OG{rei8UOJke@{2Qe(n!{)heoqzYtgE#H{yExS zd7Wn!_3_QsB_1=E&8fGnN-vzt44XAsA@hb!D_u3eV-0Y>ydhXM4EstX{BVD}e6}j( zo;f3u-R4#Po{rEA#^c&J+tv1wD*^F$UI*veJl(QtE;DDAQ{kO+PzQ~3DSgtiir7vB z7p>Hq=XdB*7cB?2V!ibgU#)9uw5Onn7V&xU(pD$4srw|2=^=W-VXx!Bhtr2=q;GSQ zlXmdjLmj$Ntjgccs@(m!pMtBDRoVMlmAO3?>x_9sIgLk)s5re1F;F(z4@AY;P-AqC zVaoFAEt=xgc^Xf0+2>m9C6l^?oUt$bmj*f~jzJu8C`O_w)_U~wlFQcp8$>;1-vOBX zIu4v;km&NeR<&rgO=Oi1oc>J2QkDVhDfQQNK{BDU_Se47|Ec3IQ66K?)keb25sG)z z(@V`hR^3@Nmzg_jI6uA#>wY~O&#D>B%vlz23YW6cHFH{CF}G?q!?wFp z4U$jS+q7ZUx3v_%HcT@{d$&1aTxBa_%-|mRYaB+=(#CR>gV0_?!mmWA&QEux>tosQ zyPJSX;7iLsK}zp4bUjVxRq@85MOSP8vnPFFOP^&`N-=Ai%NWIN(_$rkrL?4ZRTJ7| zp>Hzg^$yxL?Z+p07YW}RwF`eh*AaY1pu7faLUBdFrPOIwjVyVLX`jt0#IB zXRF?E>P{Mhc~Q-cQker(W?D7OQ_LKh)tYrVyiBjmZ%g3$js2bvaul611Efw!Jm#&(l{ll?8 zURxK#wehEWSh2kBptNDY&i*4FI&)R3B5=clX=R>yx7X7rUi(Lb2#XrOEN%0No8_X?{@bLbv z>eF^@=rD<5p)!>--kLd~3hyG}B;?&ORyW#$w^g`16&&KBUKC;)Qb=QFOB4nXsF~IT zGhzX);5LY&C0281|9o&8tHW$rZ|N*AwSfCs*02`K(nxqhuLIm%R~QNR^gw@shw`0k z{NxyP*75PMF=Jj;r1{W?dGUWyTVfHVHQ=ucw3s?`T3`6F9ts03R9x?hy$W^-OHts}3#Ss}9reRWpo9-7oZSQExaX z)ZS40K`1fl#^$8Uf-pFGV~JoJM}!KbmDf^J9uXe8c0Go41Fksa(`y|r<4RG- zH?cWvaDWkk_Abw7H1)sUfY9c{r`@ljcM47bIz6 zmuE}bD!HkR-aIO^Sln}|EXtKW1;5!-kS?S1aj4HPKm62NPhFL1&);eyId2AOYpiW( zkc?T~S-Kmw60P;Fs}Jlx*nW@n-A!^RhwTvSzj1f;tj*e|g@tvIMnicYlRvZubMQ z8LaM%yw70Vz3+c`-n?=;a>MV_7CYaMwWz#5fR}w;#Jalk()*_Mky>4Gykn%_*~u<7 zuQ_ub@#{;w<$-;oM~NUrJQ4x#DtWHvv|3Z!qNX`oRD%%__<6wjWfn)8!=hX)wRE;x zES*1JM(N=TH4XlacYLF`q$a>hE!ZJPI3^@Ily`l2&X1V37H1^l)PeFF-$E{>=@m$& zhFLgiU>)LkyO!BRavVx-1>OO2V{vsYg-od+xhW?$6f>q5@1|VTDh_bbzHo8x19v`I5gYC4sa z+NkC0m5SP^C;-3G9I{tA2o7kfjuc)`bz8_IJ z4rPADKUDkU&teS~PLF=hsc?*bN7RLelUo8}yN8EsIR`8lNY9{U}mfnEAf-HV_hP`THjut{8iwd54j8Vrh% zln_`H9kmgjGs-c4+9z1d(cC8mU5L^BDX5pHix%t}yHr}I5mBdWxYt3)v=!`O-Ji=b z%nt-Jjie`D(X^BJ6X;L;l~eJagkw$j<5@i7zv zF%ezw%BOUsDK;bL&QrOI?jdws?UeiAu;B;YJ54{9d~)0lig&XG8Z?}F%-DXZO#v{)em;ByPRpdv5nLI%)|7s z(-HqJF&6Jwj~b8JB{}y*=XaWIP;_SI^t=pyJ20n%ewfpol`ld2nOeA{V@k?9E1_o@ zFdu^{?_iX2W^&u$WN2K5oaOH!3N>))=J@`${`!Rimo(Lkg zUFV10EtoW+A;9)$yI$@Zg4jf%rB2PT+x&}GQqD>7>E-i_R$Sp8_5}2!6)FQCW+ePemC7?6kjZG-@@xK2-;Kl))1aw_Ni}H5W!F5=gYSl} zA!UnmQ7d!{#Jv0`mv=C__QVFSqvpJ})FZ$bD(J#^cJwWw1uVZHQoMRu`>Y0Bl>doQ`~;&vb5oRjk$> zQ4{km3Rwo+#|k8ZE)w%+Gd)e~3LQ7~hmZAC750aN(f_~oyl_t>ye{$rB6B;JQk!L8 z_@=J4MXbod{-2rXRJ|FD==AoRKVHs0LClFgY+7dC0}F;d#D`XBAd@)Ukf0weKUT|( zt5olIEKpYSx|~Y2(DCSsB^?ZMcB;kYXM@C&d6Q$*iQ0o|*1UtNJvr0vQ;jB{nrPDX za4AgQCiRZVIvXvq26sEu!P74UiMh0h;y@>MJPz^fR3{nV_~2BZ<-xmm!dFRg?W~tG z_Cgl7lo1=#!rT!KTFP9Yb<4b;cPaiy zK9Azw9PjM1^kS2;da|i=C4+0SNr^CshBM8XH>7y`ybAMnZ-4mfe%Q~to-oq+?F}FN zke;ZBBj@15p!Dz=(&La}DUMNlMJv_E=mlQgiYvai1{^q%(6dua-|8-J|J5F#$ifq1o?X*)TXqldOf;Cj+3h7CK87hldcto@`l2?iFK?2D_^h-2W z^3U*R{QGl8{eM1}Uwc-gKH3}L3!kHELL<3((%Zv?Q5MK(%#HM9-6Zr68H2y<{Z(zngCX~dz zapjGrwAS*vdkqFeXTAZ-87`hn=dQf*WN-L|2#1(BBTKIAc>Il!o@}3|AE(c2p0^$` z1vDa1r&_@!#)9j-6`}E)3^X*NY^#r4(tB=2ERaT=>PJ+J@^%-qbs)}%T6B4(0+f)5 zsAgUPkF^5dsi$A*S2>B;I!=aVqu3UWp=o_*y7F<*^F6r@D7Jw$b8YTDTp z?AJryDYN*8Ny&brRN>Sd-QqorXi?685_a}_Y>7InOe!q8}5Y-?RS`KD*d@} ze=lbEFNSH-r@GW*U(7mkk=3TUYrKO0AJV7Z6bZSBdbb<@b0ik0Kv~xuZ@Nh9_#%Cl zbWo>1cJv~vukgnCo2AdZ!=mtl+u)rpF$%*luIb)k(Y>|;bKG!&`b(C>E}|8aXynXw zqDF~1fS$I1Lpe;eza)1ebdOsCy3kO~C?!d=+c~D0dd@~i>M$?kj?i6WaYWlr^lQs{ z{bp&W^tLnm=ox9VH^F~KI^nfQvoeybiN`JOdBeQZ@Ai)J4vfPt&hbXVw?s-MA$kIo z&IPSG3$d?i!zfr3>|!pSr$#=&Y=0?dihskYFe-_@hFBAWAF)QJ-tfINN*D3=lyaWz z7W`>;P)=d5d=PX4%ceI0UJ(Jl@bUtWWbk&&@SKYq{62pr;u_PXcyBS{i{ikSJ%F(J zspo#PvpYzX1mFyZQw`}7>t*YmUSdx78pQH~c!`r{_&t7F4l)=!q;Z&3=w-aDH!TLzSS*rI_n+?t*g&6(+<=~d|JlQ` z)o(%!6Rc~s)c+nUL*th^uEj4!!rsWg;+IBdzt$MD^K(*yYkMQ-CB|5pf6v+QA31c? zbaqB&|E7^hpMgU#u^0cakd^zy4R$+{pfQ3U>Pvb}B{;y4FUUcU=kqVg#? zDp8iJ*&?%@#!WBJC*v|83Pd6qTh(bz>!`LG|)w!xrTlqQxnv_;52ih#B>m?vrj zR&i>`vIb{|Or$Il?){LCdXQ);qieRYkFj%svl4?+)LU?-kG81m?~CAsgoNEj^Lr^LjUO^!ryVZN{HYbLC+Av2XYs&b>UncC+h1q`QzOJ zqNEu6M#M%Dvr$Yhk89Pd%v7BE^N`$7(2>sMgJ+3&H;LGKg0Q`a=^~Styn6Y%CB(Rirjcg^={k@i!QYw5T(6xe`r(^Vx9BY%{D1|Qfa~$ z@C1+gdb7&x*q%vq*-fDU_@xkUE)d<~UAa@6_lImrcLq|C8k24h>$xdR(w3$qq|ktx<52J$p$!kQhU&?Fg#n0d3lH3O#ASU;M<`ous|(s zjt?2*-JRs#2fNpIr(p#JNRe7$f9RnkL}iDljg%Sd?)14ouO;TnR=2|PZiVNYWjE-v z3IBTjh`jd-SzUj0f9RQ{9JIGQ=_dR?l4J^Ib@~?kuGZaYTyRj{AIeEe3btxyV=mby zOWWBMu+ZDyYNY)gDL&|QD^>h^fVw&91fWQ0b|qR}{yV&RG$}5)Q&ZT8UM?7@ku3i; zawOzycBQ#5QK3UHXPBuae&mJ%rKz^7#HxDdzw874gbxZYFFuf3EmK z{EcU>%2(H8R)ofFBAtUmF|Bbj^q9z4oNnp$iLZRUKeRAub?2(x@gnMTCz;|xy11ll zVOO@IORzR3nGRfH6A%H?^BXnG&M9#$lj97$p>rKei+(W#>ljy}7~@iv#3WaMwv^V$ zTR6)BXW|Ky?yYuC7k6wQ&g2`xmA4k`3o(Kkywgo?qL4h!2NXdfVJ2)XptbW@tH+Ds zt4Mm>li0XX+$#RQU5JZo7qkXod|CbNBFS|qd)M6QJ}$D=htHQNqvJkCyo@cbQBL$5 zCw^XQlV~g7$cJiAsm2}5X0M0Yp6Sd8ri#KJ_`C!+vu&6km@>?sof}9G@kuwgY?_jL zf?^FFJKMrkZ=Yg45szLn)jQh-!2)X?xA~8aIc;srG!`b0_L=~<_aPk`5O8ig)qTLZ zw=t4VZc0<)k}`vnMA(wI6^{6*mU-#Vkn6cnB)v!}CQ&QQ)`H10O*Nag7SPg~?YiKeOj?6x6Rj6EitWre?zbOe zoMVNv@*wCc8eDO>$iYYi_3N$T*z6IFw0;Y|csBn>6VZI{|*2xLBV)n_`np zC(=5}gLF018mE{ZGHorOYs9yViT3cg*4Ffw5Q!gcimkWZv_BM=WH}jo;?e8)kezu$ zX0}t@DxR{waq!!AQ?Z-cjj9?`)YME^yt=j)d@i@b6T?jSOr|Zfz`{ea&2&s=#=aej zkN>>(sQd*eg%JjYjB%i&Nx#4eH?uCO2^h&woiZpWy6es}cm06dQ-0U3(_TILz1%rW zm1$pw0c&Bc9djYT+;tw5yC8}0G?ud9AZ1BU1@~MrE}0*s)CNk6`$9af^7^^3ihvKy zCfV7FK2CeW;Vi<_y!Oe=Nc4CZ=vNz{bH)XywJ{t~KJp3g##_wb%XwXV#<^Mw!EC`v z7+w?8y1iH>jzxc(CEL~UG7L35mK z3Valta?dC?enZ^u39oD7LVUt;oZ@7fi0O|Pt4 zDNS^ySUOW|Za{cc$%K-nNYheOMjL|x+Cn?BG_(*(x ziuL5KcAo5*vJYn;v~KqSrh0^X#Wy>|JJA|>P#a>kHYu%fmT5(lroW+Wa_MbcQfnX` zc5ZEmiRRl(MiXj%(9k&A)P|nWb|}BtTJWV@I%4qKR&hpm<>iy$p((JgY%Tc9KyPo~ zTHyS~E+$3K35~v}x>7sI)0raG8#5a%*n=qT4#5f6b1UqKjW>%fXycq3m$O%#6oraA zX&?8yDH=$?%i0C*67)n^Rw^kkV*ARDIrnaw_YV39s-K%@T_eaR61H*_J+T-K5KYoWd7W=>V8Z`S)x{rS= z*L-*I+1I{xE!z8?_$;l3JwQ8n(VBnONuwC!Yv10!=%sJ<&lhbwSr$8aBZc0+xO}3R{eq__@<8d z3spy`%seQhBaot@j}a?>5;6qNDN-v;d~SD;YDIH(SEJe&JjJleC?^mv0KF7vg53JL z_0Ckp6lAVo#*th#Xh^50;#HRqICO*P#0k<-Dy=ULx+6VTq*m5OH8d^!9dY5rWmymUJ>EsnkKKcQ4LU&~sqNsqE|S}P;+1RK+Ve<*@;@$W zr;ScGj%I=*$7D7)II*iW-XZ3QZ?$XUdcq_7I?8Ixgmw*Yb8mKb%;S&Lhejr)9WN1e zt;9s@JcSlIPkafQzYRJe?Zp&G+@G}Y?%!cgI3!b??h2U1Vo^aoI^gJ)-i|VlyJOyW zQ7y?{-yg1tTpN#F-{30ifW_#UF5@Hf%QiX@e_ggkEzoB``#gM6XC~&^>1)*jBdlSF ztEbu%wfnE>YK2t`F|l35cuF>iEwFcyeN>wogt?4_zlabkOJ~7Ozh{7GYLpDO5X(3* zTl7k(59h+Z=w=XE8nM&URPC~}Y@9!)5wlpoNcfR`(RIsaVEdSNfQhCb9iZRWq2Df{ z+9y#WIQyJmmxTBT+lo}B57O$#(7g%H#i5@q@gCNkUe34LR^TLB^b1G%4Lfz+$p0Ss zS6g7kG=C?54qYRlCt3PBVX7Be+b`grZ9?z)7Q}@?CrkC}8%iM`g@WDkF~I#5@B(ZV za%4xy$jx%jnk+Od!?>CE$*2X!NVo-MbuG*-T9rxQM_&mt)x>D=!rmH<*^9e}&QRV8 z)<(xQy(bTS(*$X37`25FW#0knGoXFa*Ciu@mdP6)m@g%HwmXL%Px4eFYL=AZ+(O=V zXYvtF`E`U-O3~jZkUoZMEG$)=@_YPKt&>+C-iH$!gcTwYM#x9ZwI1IvN|<^t&Ni6+ z^q;xSP5<+FoJ!JqGFIf(@02X{tdUo8)p3@c7&&|{81rZ759?|6p1_HXUg(tc9o46UN zk8e1@heec!*AUFvJ>PX75yH4e{RFWcxMW-};QAA;=|9CcQGQhJ-|P7Qy5~@qMISX-SA0Wf4OdP5 z7~JN0ttFk$lt;p6`!ypDUREn8Ob0Z6qFk;5EK_u&ez znts`UgKqU<1!I9spTHV1v(Sph0Ry(tZ%-(1JCPc^`nv#b9mnc(ciEYNI1h`}DQw*T*- zdQN$zpRqfX=@tC=pgazJn-`sfCo6{Fiy01OX@zYVTGVfFlFN@)z$&|%T$U>Et*DyW z;@i%&;AbfDKy)-etH`Q1MI)(3Na@~Dh|L@2e%Co9NM}jlrpk1Nah@zC61MjPL$(s@ z!ON}+q}!P74Csp)_Yb*6C3@N?5q4KjDe8v=Xxr#?C@gx{EYq2@M%%inf{Yp?I$9}h zIevp!anQrra;{3mt1$WB2bpnGA)h1CVYM8@ESjk;g&Fs(gU@NHosRP*m2E?B>J0L? z(A9Xy`PXKw^DgbLBjL_II$k|@?7S5txX`EFcnJ1c%`VO6NcafO2s)I{eRLd$aZi*( zKFwB6Io&saB~5*qKR_RdLf1y2--|-O3+OdEhqB8j03+Y@amvsi@M~YRT?e=IJgxoZ zDEt;c?ERtcx1ta}?u97C+9*V&Py2^7%*9(cdB~eI8#Tbx&3)M-#n@j_czBnWMByI= z{Gx!-d`HpHQQBSo;jhp#M)fj$*w^5nio%m+KRr)5=beC`+44#4h|$xUX^*Dj*%K(~ z43tCq=&OW3=Lqg*_2qb~r`#3H_H1?D9z3o7u7*NPX-i1JS6dWUUkrXq->fNjb#8ng zIGsvyI)>4A^?mqFjA}>pDgI@dgMt+2wYykTEPqVj0%KIdEQy3)XrPpq!DZOuf@5(G zh*O62(SJkV^Ukw@Bam-X^8QtGN*^rFn}799Og;?&$E?7yfp4P{$d%ZqJV{fDRlunt zoM-A9RAls`wk~{s!*8IH#khpKT_%H+<7L1hVL5EEdW{mblJ!Gra0a8ZFKKg!yr@SsUimDn;*`;O_X)&I? zD$Z>0F%;1mdSA8gVU=0%iMXhq0m+gZk=l}ScbRCzh_9$@H7wbprE?$r;C7CM4gL%D z5!jEdux_`*iY`FLFUP3=T3^!n^?1$Quv{Q*hMkkn0UbY&euzj1#&7?(@zcCGkFE~i zaHH?mrjxJ_7q;f}>Okq{*-J$_l@kCt7Uie^OsWqF#e9XvpS|-5ULFg_% zUZLFRiSB3__~5VdO9gSWQ(u=Fz=_1An_)XHxym5DG1wD+6_O_}j>Jjq{%}us%#&eg z<&<@Om*s@$jz4t;ldB1^xk6xpAASk`qFf~TRuJXIzOQ8uPUX`t(GYMn`n4GYe?q2G z&&_H~>cKidqSeE@A=DN7J<@v2n+9Je+Tcy~3uUbGOPrOb-ybOHY+1?{v4yO141U`C zF<;Yh33WU@x8~<0NE0-U3$Tfp2U;hr#fvtph1i)B8XwQ?&0;jPBgoAvEJPuexbW?&la`F{<@jHiJ7z(cax7Kb3cQmS9#hfOP%d&lM zr8KL|ah0FB%{l0#|H`x_^xwI&3X*jM{BZ;iT)uiWf6#<7(%o$4;kwC0D#S1-Ug{H`+(n7G+$PuU`kV;n4b6 z9o)%7>zNH1wI^j}!zXxG)0K{rU;mGCAFby$#L8(;a2q~aA8VVL)F^+nUW1%i>7tBI z_>6{-=j8IJH-DCYx?eyXPG4A!(0CprR-4kTp@8~D=z8a`H5O?ueC0Uh zh{*U@%hc1bRvH8wZ4u(iBjNp#afno@h?o{<0TJkVyCI?g4^^2+EbzVdSfm`>XW$&e)&gn`h+M+=?k2~uaIm-mCngEx z>*)995b?RYpWJ*E-=UfeUlr+nz6~;n znOhsBhh+6nQT_Rm{ymhcG&M3E8^zuvF?mG*@qo#SH}T%8X7$l&8>{|N^=xqF3hg9~ zja>e#?=SCrboV$eRzJ}2m85NXiP6>jDMGz?4JkmWM^zo2bG zr9qNg9;D?u`jD@ucXoWA;E!@e_JU{$V)On-iJzdvy}*Uc@+0yG@WxFK&RAi*jmxqrJ}e%x3#HVw9=yqx+CX!b>9q-^jqTUZr0lTSRy4 zE$TgbPGL1`)oI3%{~7-jzXf`;QKY&z-Nz&0uX`BFTFew?i{v-p&Ui~bjRK?;M)QNw zQw>gFDj9t#`0qJ~djLJ{49*ngHPWx|31#T(bz~5KSG+wnv^Xg-u%Vu-z-lmk;SrF@ zBH^KtfiG)N3a6aA*p6?EV-KV{z5*Ujzh#M9=@(bPgNN}9A# zdZC3DsUn&t?X*yQL2$K-t|_HDrCh>AEvx&{+WJ~9s|c>k#S4hKDDEx+x(^Yt2;zEq z-AzEg1xk0jbTvYeO}Wh^X`Ao&pA__cm-ox_OwL@+%sF$;nREWv-#>jnJX~JfYgsoW zw7xHK?<-{*FWa`yo^t9RYb{uz6ZgK18SdOdhWTaV!VTroK2GQ-y$B&;edc*x5ejIQ zjY_A-t~*zE``(R@+V8il+aClHA<%qYwOg7skf$=<+RRP-%#XR6^~;~ZPiH#tFl{1t zC(YEHWw)Ypex;aP>lA@7IL(Q58!&^s?)}#+7+L8TOMg+$@ey55GCx5BFC5LWewT-ELZG6>0=UfPpkA!)647fTNT1&xra z1js=6ILvIZj>|L6Un`~!x=ml7H+=Z@`Pgm!^4_o@7JIOQX!Y*9ux>{AGvW8Mu1=o= zMEc$h+K~JV#zSS}kUtMOM%%03^X!Nv42CFGu!kDTmn058G6&PE4x?8YD zV(;vT`904|aWhQmzg8+iPf5T) zTB1n!(&8|>`{nYWw%5hN@_FD*!e%;5=!bM4QBy)z4rWUhNX_Ci#WQ%F0pu?kmt04bMcYD@HLvc`C&gLl8VApntVDY{M7!d{ozQx{1qm@h7SY`!c61Ka#m$Af<_1$G%u2}(- z@!jQGbBn^d=DRG*s+U=pweJZx3B!}$rdFA$9iMeQ!Pqbqjg2~ zinmsrTamu9W~CpVggc%b_tgBS#ywsA^iteuK0KtfMM-D=rgqGUOj;I8a~1l*N_y5u6qcxQ`}hujmeC z5cB`b9Sb*?!_qBF_R{gZg+vdTK(W(&b!@F55~bfN=IzC-6^DoklXu%swX;ksIEmf% zSa0{*yuIh@$Z8KB*Nxvk7oAHW-_9vO%$K2SqqH8ON)fFWy(`Uku0a!s#GLbR>E}>p zwTtE_p*Mj6qbPK4p$^!!8*zR^IoZe1{Mg-4<6#p%1xg{$zV@@Rgjcj$_b>d%vSYN* zj;Ql%v(%`f1wT?JKr>FO&wqu8DkEP{NCvmPZWoSsH*~n;@%69Pb}uB_Ya6JY`RjLL zU8EUG=j&cLYT+n1!`e6$bR#_@5P}R&)iLf|KY#s5%&cqe@!q!yurT5&3IkS5G zTj1$v=FY^-O||>)XEk1GjjjH34I5z%XF}g9kx|Gw0-HeiEbCWPYrCEV z#*LsosZt|U$AiIQw3pJn0v;0Ay`!B^R$oE?D6?o>lRom%y1QX5ZguxG?1qGBwUF7x z1;#Mo?!>Wgsgr`h5h<8z>>YJ38 za#oE{xOIi@1HG}Z=7Sjmczv1D(0A zNKEKb??3pJ$1Xmk-qX=9q>Vn~F5`~B+Y=*PSer9Q3kcpGjL0l;8|ELX=d|F*{(~s< zoX;*sOZ^ykcAWW#pKJmCtlG*G&CGg}41@_z?bQjK^wAv{moNM~mPa3&qIDd^mBA3Xn`Fd)rR_YkJ7ymHiYThFb{zn%KLlAxwY28 zn)`jHU{A!wV#bQOqUs~K!0g~uX=hIizYkbvG>?v|Cmt%`{R-oGh4w3~ivh?@iI*d( zEMYNmmUT{yIz|*ng1%o~5G3CMj4e=DKOfvTV!tZL;KhiqT{je~^?f)hz|7Py&m7E? zh&*DDr5B^tbNfge3~Z1-E80FP>%;q%ut4X>!W%?`LnjG6>g<7?4O87@n`&Y^T{Pcw zfnP!|NY@2iw+++`UQb{(gVz`1ImJ|{&kD{e(Y`C8SA=pkbhD6+|)zdVPipK1rc`IX(VXX z+0_W!Xcnl5SRupK0ju2VqT>g^%exM-bov(3U9`sLNb`Vm40(AqaYQKtc!yi?SCpS5 z#MV`#JSshc{U~2WcfF}{TJJ=@hRs3}WId43Ac6-;#0}V6;9&u~M`>#Y4mHVltjE7% zksQmZHOvOd@-KsWQF6c2&XVy*GEP2OA$jVdKQPzW z8tK$S1*N9DSs*QRTdxV0k#wd{Ufln!I-gUVg;sHdI2u++EO5NP3ID$x5Yq1MAZx<= z#4YgsJkB-3&EeMK<;-3vbxT|zA_fLV6e|S46J^>s{IlB zBcK{*U04T<7a?(zWadtI;C<96^n69R%yX;w(#M?GE0~A9H*W4#h@DOrcowaTw|MCU zEH}6!(6rGTCD2~9 z1lsF#?u4HMG?-Y&;!svqzfKIeS>BkA=7zSOqeDiWVS%w|fgv3$qzfi3@Y&`n7RGwC z!>2iSONH(nXbz_0zHHQy`obVw#}^SRP&^ESaMd3GS45b>xzIquuLIiMqz;xF-?6)4 zKb{_Q=A5Zs63|xBrwU0sr9uzc*=q)HKhuI{u!>7)menUqhC+CPq)rkK+W8~5iPwE5 z^to9K%FDn}vB3F$;@2hx|A{dek&g~~r}W7~2Y&QUflnKJ7@*k;dE!vPH* z+QcTB4IF5Pf8u`fBQU@Z@EiCM@J-~4NB01K6r4}82y5b;Y!4fiTF@t#0I}V4C_noO zZ1`DkGSA%wuaEph5B!B(m;L$KAunwHbFM<8#8*V*zeR5N_K|MwBGxTtrIqV8ahOxn z(7K0ZmwA7sq!s`Jn&)^#rkUyL@oUEv!V#bWUUEQ$6< zDnN6`3A)V&cb|M7oGNMb0!`E0^%8uF9Fnt~__fS){+;Uab|>)AND`mb?VWrx4$2dw#`{W{_Qbi< zEQ6kD5l{GQq;X=Z2;>X#Yi!K=CEg&8|1WwE{tG{~c`?>%YInqqLB0Qvy9n~{1(MOd z9TG#DUCYDFinvD?(Hp$}5O*pn30h-(EKXTbg?hXps0b@LJ4+UNJA$n@M^_ zAkEE}hLy4$rK85_l!%LZkX=MX8KcO*$8C(rIrw^n4sL6@$Zsb3H^r5qv3}|1Sl`z7 z<5)ksW*FXjh?lQ>#{DHcc(+Q+-9rN!7VquA8kPjz;L?DRxyq>@mIk!giyjj#rxjcG zY=kvE8$ZvR7|;!Yq)Er^;$BW_H*Ev;vP$=Aayxw9H(<0mzdo;d9MN+gXMr|wC?h*G zZ{CNoMRIo`ExrTxrc2Qx?^17>yxJ}FrGBVtT!%uAT`ca#H}gSAw^_pIdp{K06&~y> zlW%HWs#N6BZQkx7-GVwQUl@PEz|RrsDcj4TFN3y!YTYQjO^=ss&QJLJut%fWU}vx~hNk=LPqMp(JQLS>V7TjzNVELZwrA*eZ{fptUz z?6N4nPs08YZQA$2lZ>JsICZn7zYE`JY2rXlHXeRxrv1FsB6Yy3?Gd-NuF}0tn(Bs6 zO=Ys$vb0BSY+%8k^l1s^iy!;+Z@1`E_sx>f+xrFSZN1@Svoy~=3MF*>e@oytKIG=# zgV*$bE2C2_gT`A(ohdKee5YrBQj+^x$!bH}QAz82NHSp+ejoM}2F<YBZH&&?g&3 zXdlKu;7!lI|MbzpUW@bbb+NEOnx|6PrC2j8m|Isk?OpF7@7>;XOY%f#YM;Cg78q97 zZYc$JgdOU=gn*+{&ux`rJ)`R2d5a_11NDC()kwRcE#JC^o3s`Bpc1U!T8I~~+H>Bwo6R>MNHPj-TeaUI$Y-6_^a?6ZtM`GMdi_>-#AEQd~9w`UC~ z29{mn^FpIkN-=|G-*~Rsw*y`+Id$9Wb1=(3FPOzRnq8ak5{YlyTs}_plnH0aOQpAC zrSo6@oI37(x>sxOPD&CXx0oG~xA(=nca#kwDTeEFoEh%ky@o5? zjdp44WBF&iG`|Z$%(_L3fg;Ui8{11I`Vu|?=l(o;ZHRcIZX@x|)_rFeCheP7&+p@4 z&5cC)B!S9P=aXb09d#H2zriV4Y`+ZDUWmZI5D!8L-I&y67H(`D>Y7wzz!f&P9J7=N}Zv&_O^L_f>TyWPw z)eUMvf0@x=t;*m0e}!ivzc1A}8@OS~;IYo4-}>aggb|sCr>IbmJ8P<~^WRoVH+*_t zXEj1IAr?@nNnVzTQf-5}#~1#jB$b@?&&&|Qx|Ib*f5*ESw11#C)PCSE0~#CAHe`7| z8gZ~NABTms#18&_ZVSzRlQ5ISbdU|-nKjXP!kp&ld7<_Uda4VnEKxQTI|2TXxKFD_ z*{a7oMRg(3m@u=kKJQXnXD9l2C+<8NCQJ`4R+Z?zTX1hI?nP`1l((aOp|lA(HzDWm zQ3l1dK`Y@Y&qGHT?${qRQoN-#9lE%a5&3oGpqUGPqX)RDqu{r+vnkL?XJ8w4Fv@eb z?(w==24_W#hF!W>qO^sk6tg{$sM7nk+w~ooH|;g>X`Tx&$4{~H5giehk74#SV099< zZgO5$XPHwG$-O6Nv=zCJtg#17nj=kw4`)KO8ZAav2(8L7894=vEE~p6D6$>@@}PAr ztaREbZy9WeHG`JEuJS1FPJa5ECFag3aFr9b@(>k2UJ&;M&1RMz+nMq#|Lj(9|FP3U za#N7A!ov4y(;*$Aw1nhUL53ulTJ`N8`g0K65d=e+6-#hnIK@mznak zSrn%C$)!QUqO}5Ton>BA@oWQa!|r9~VKX&jvn76q2aYn(^xnR%zP7&AMEnVp_j+;$sqd2h`Ho}y?L;2X7_ z%xqq8L&L_b<^@{NT!zG(SN18Z6FA-5(T?7iU6ZM+0u zeaUT@!P57HFJIAwhcUJZy!eVL2e*OvnM;G-v#i}_9|HXCA;90J`}e5W<8k=5+Xpgm zMo70pw`^?z!ViKGB9=<}_pl8Zsqi?)m8sSi!W5+brLm>Om_cNc)wFUR#^_lJy70yr zazVm->lP2n_w)Gy_NIYz z49nI?ZdZX=h)8i;q&dml$&u1T&s+ASvm>SPp0`tmO}_{ah&VCeZP zWa^^+Pwd(vyqY-xW2;3Iu4?gX5q6rE@A2_4(N)^ez>2qMZ0LL2kn-0Wu zV42*VTb)*E7$`s3%Xbn-8J5EXm=kcdNsaj6kjk8gAv@{u)4kB;IG`cL`%d-Rr7`dv zm~skje+wDX-<1Uz57+m?m#r}@KOP}$bQ&MUim5klh#=~Gq>Cj=S=ER%zW_Nr)i@Ny z9l#2^Lxgv#W`lig`{5L3ww1EL--C1qN%x0Cy3g7pUu>O9vQW)xU3RR`b~$3%t~_F1 zX=zk`Ze|wE;~{yrhcL_UKup6c<$6fFHj3&zaSPpp4z@i(`C@;8jdT#)hV5={S5SU7 zNLu%xJT^Gm?Lf4YW<*QTtqRKaAZZ#9t%zu&7a*@)K+={%?-|G~@WsZY{m1DM@Ig5I z#>mu)(KATvUDC_Ai(v-qK^E{srV5+a86^McgcL#tZSy##0_79|Yw{5jvyK_RbHUJ4 z#psJa4>Y=Q&dKtQdAk?qIITa9b})@oWs75SqNBXjf&IQME? zzp`X=gTeiQo%s-{qX-^Ik?Z~&_PUUF93X5S(kV28Qc4ihJwr+6Gb=2YA4>FuRFuJmaS)CG@4M?er>QLb9xTu1bHHDAIEkxiB;l zR~*3Jc+?-*Z-=$=hzCL>f za9m2IZB+u^Kh;s{ED!@9h2?Vx2{U=UJ?6xgroSMoi2gPi0l}FbJ z2at-il3~W_5#NS26O$1&22mc8Z+tr}&=)czw~8~1@lE5L?lXuJ-P|3T@kOvGexA{6 z=qgXx&$sb|95CUjXjI%4;&+YvV-b5{&7Ng$j(F;TB^dX9>=q5MNy75LK#ZD?u&d}= zZZH5|{KY*Y|b$PP?_bOfBp#tr*8$r7vLtY-|&B;rIS1q?GUF0^i zK&FzHH^jH6m(7Yf4g0M=izZ-JdnIF1;AT9v;P!rCGZKFi#uPQL(Y78@V- z8O4902jWGew83L-D9B0o)igYw3hxxYDrdA$Bbw5;qnriG0k@{eWX^TE4wA=aTB9chMhfKJPDrzs+|lM{-!IuN#%J32`un0W~L8jP1;+vxv#1 zio90ok+SPpy0x^&>4OCgqNo9h27aO@@@W816uA-OO;^d?$vbtG_G*VyTiHB_o)YIG z`Xp}+GxWDcu~Ux1-|i@VCBR+b)qHfs+7}}aVXMTBk3E~8mDZU*vB^HFV>_@xIJ3q* z40$rf4?9c8F*#RGJF~Q%41 z9$8t6Z!B5}h*BHEvJIFpVR{iIlII5Eq0fL%8SMG5VqGQrrWN!Ja(TXV zCrKZ93KDgxoOrOj;CHn?9F_Xa))}xNN2pvI@Ogg>fBRQKi5E$5!@2+UK)~t z__7vOn=D)Lk$*t~knIZEPMl}=W2W&Pt8NBjWaC^ySR3hR!na;<=sml}_epiS*z4ye z84AZ_e~+VCR~zp;?{`A387op;Ug)G$&(PcOo!$YNhegrk0fh!DBnymCCSk^%b+t*= zh#{ii0Yh7u5LqR|A#;}28&fP~t%qEZI1}1pk$3Gf7I^#sv)C>V$Fr*s1lnFeOjy

Zh>akspFMJ(V{cVsrC3L)Vt>np=yjbWfwSnvy^>>?PtnKoUxv$%ERV}5y zYaS%T-QG!%phUHms-8f)-8~5rX&gW_1dr#u>bGJq=m%|fwXxI2m}kH_-{crh-i+!;6q!qv5W->-?fQk=stwL%VsBh36?VoSLXlZO7#33drgmn zca=v|_|5)Xjvuc%esb-`eRDlCP`_xcP@{>_TD|&XtpZs;xrt++0X=9@$OZ(2~QDYjkE+5S0-jUDa&#-{2N91}sy1zuQZk2%fq;1%7- z#zL+R3;pQ%eWB*-Y{CrRI=kk?bMWO1HnyZxqaK|34Uy$_d6D-&I{g|?lbT|x8kW^H9Eu?ya#dy z^kLJ`(hFQ^LYNJ_TSht6_n4?T{x0a#gN+99?Vbd|c7eCO=KrkMtlwv|g!Fwg5lze- z(qH95x+|%UAhqOlhJAN92&7J`NlZ9dt$`t&fEs8*y328DEeySpI~xP7jjd>-=NotR zY7Et-(Ygc!G10n|uyDe_i)vjs4sBYr==h6e3r}l`t4nPc47TlI%_}>461W}q&&7Ae z2TsiOKI+~FuBaO4xR749pdP)pF%GoVGB!5auIPLIl#O~m9Wm5iwsDRdEw(S(2Dir< z9T#*ClzjaSyAaY`rIz4%lwO>F{0(~^O0Oy1Hfjy}UcRmm-&Tl`QlbkdTv<2Rx)>?N zw;f++Pdcr+ySns?6!8KRi~SQI1=a$EuKPRaxW20_d+)dh9xDraj0s%vPQM6@O0)P1 zs92xhD?a1bOsy`Rouij;JOtB<);+U9F$i; z3PQ)9DyNDdZD}XWQuv#hDT=TTNVdOlbx2hXL`n~`zzIauB_DndFhYwV+a-F{hw~mF z3Lq{u{-f7_1^mq+Kr?3(Kf4}pjGA^0&XaDwBp8p8W+ z)>ZheqZJ%!@i`=QiaC`IdwSx{Siph&xrhl3E%G7Oi>F;f-oQHtoAp}XkH?*e1Bx19 z!&*KlXJaPzh_y1%mICRZrSiy?I9;M~Oly_&v3>L}a=dS@`55vj&TP!ohFM{iH2N1M zmwA4x-R!kr=8&c#rQ=j@iF#~ke>ih~TAWy#77GN45yzqbU0Rj;e>}Mv&)HL5-097! zkGgCr0Z7A6`X9`R!m< zmS4x&+*(=Q63nPzf!MHCv?A4oE$}l=@MQ)fnsmrgVjvex%hR2rvCPJnIX{!)94e2E{%dc6o6$#1J1G(ydR)wZf? z`bM3&SCgi#)K(bV4e79c4hWi&P9a^EXL#tEsf%@yWeZm!%O&{s=$Ki!bOBhuvRoXb zr!mXcYSqR7*EEB9b8hB^cNFfm4jv0xQR-mWDQepf6+SNpG7QFy?HRC3Wa)EZ{XEj4 ztsIF~*bRHaVwKwp`(Hu*>0RMtD`G@|9whmN89fmSv%r}kIBRgYkO1iWzBz+`?MZ&d z!%j_a>m&!FzPrk;+!JL6#GKgzl-!t8+%+~7Xt}4g6;0C1_Ez{@8NEgOm02(8XV$}OXBcd3^j>VD z(5*-R3nc+wb9l2Niun`I$ZkP^-2%z7NZ&XdPvKApviU#K*evY>9r1DF`y=^ljl;HL z|3KpaXjPU~+d*1^#7HA@+5+!4nnm*z_>c}1STh4-;*9Ajq6gP659}+oi+ev6nuOGVG#ROYG_~Ny zbLh!m4;T*CNHMS}rV(~{=?HLQ8nhu@`@;aJ(n4lQQjd0Feo*}s^Gd*h56EwaRlKT~ z483Lp=?ewzCF1RG=HD<#x_#-4yZ6Rg*H-!zW1i+}*Zg6KNNAi!?>~TfO<*BymL-CD=qRGvX=l>=$*?rcVubsvsjP9D z4k_Si8SrWt(5TH8LmO%BruCVDnLyIf$i>k!%!q7bYP(;04PM#bEZm9r;jCHErowOK z%5%an&s_(HS9<4f2QIrqF`LHtu6ls4mOaY1bs=OyUcNUA`tpeUm&k0a+ISzxOxrN$ zV7;~i!3cVOZ3VQ)7+GW+wJXx=Pj#}4OMa@Cc__6+-eGiMkalYpKR& zN2w#f#Br|~*XpVlnHMatd#ZN%k68yFCRW!is$F1Sxzt>Pr>?9uuas*4?bh0->S}85 zG-odO@%Fh-*3{IlSn>Fiix#aiFCQ$H9(0S_2TR7dtzrT;12!Wz6Sf<_R83Vdiy7+1 zGs6ySBeR*ojr0&U%JLqr_2&RD1jj*a?@eHa6F6=vV1}P9u3gOPmORduR4-v!OHiZn z7zsx~X7BOW?kfE4u9Md5)9;w}+pDGhL*AM6`ft|%#qi<0 zOvlm>7G&u@r(uF0!SK-UA)A`C9#zwpzy78q`kp0@5lggfZ3i}q*Mj$)=Vuk)J85)5 zu;S_G9=@x6#p=#k!=Id8Rb-#})WiuBCr>DNqNaM{#7U3WRu@+@`aW`5{({=4@>i~0 zHMbzTOYO)aYFYRj4&U;T*lrw;9^Aii7Y1790h=0%^?Hb0vFYcSmn-*qbE1?00oxu~AqTUWERq;C0*bV^YnOXQeFgHD`3 zv62BVUxS#z7w=t&XSg-}rxG6R^FCjoR{aY&vYY$V}gS6*5!7dypvx zDNO{_sZJcwH-9)0v>?*POvdP&rvefv#RH)UW9%O&7sjmY2wt4h7M}5x;z0sZ^A0`J z((#uDrlZu9!1PE}-2xrIGL*$2b#}v|8!5&xi$l6Sb1X9=J^Wc7i$~h^#AKF$l*LSA zLy+eGWK85voH%(>!QjxqC_#T0u(|i&TR7>S=r4LuF=bxSvy&eMHHjb5qI<^P z8MDW9DYBZ{FN$jziDW?jiFQ%vVLGSY^piizYeSwJr(UE+9{hFDMf_HQM!pB>Y+U=# b!F{@ + * + * 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_MICOAIR743_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MICOAIR743_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 MicoAir743 board provides the following clock sources: + * + * X1: 8 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 64 MHz RC factory-trimmed + * HSE: 8 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 8000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 8,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (8,000,000 / 1) * 120 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 480kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 20 MHz Max for now - more reliable on some boards than 25 MHz + * 20 MHz = PLL1Q/(2*div), div = PLL1Q/(2*freq), div = 6 = 240 / 40 + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (6 << 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 (6 << 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 /* PA10 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */ +#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ + + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_2 /* PB8 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_2 /* PB9 */ + +/* 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_2 /* PC2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */ + + + +/* 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_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) + +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) + +#endif /*__NUTTX_CONFIG_MICOAIR743_INCLUDE_BOARD_H */ diff --git a/boards/micoair/h743/nuttx-config/include/board_dma_map.h b/boards/micoair/h743/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..ba3f15eb97 --- /dev/null +++ b/boards/micoair/h743/nuttx-config/include/board_dma_map.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * 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_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */ diff --git a/boards/micoair/h743/nuttx-config/nsh/defconfig b/boards/micoair/h743/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..9e4db72b90 --- /dev/null +++ b/boards/micoair/h743/nuttx-config/nsh/defconfig @@ -0,0 +1,245 @@ +# +# 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_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/micoair/h743/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=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_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_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="MicoAir743" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="MicoAir" +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_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_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_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld b/boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..511ef26242 --- /dev/null +++ b/boards/micoair/h743/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/micoair/h743/nuttx-config/scripts/script.ld b/boards/micoair/h743/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..1dc1a0ef97 --- /dev/null +++ b/boards/micoair/h743/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/micoair/h743/src/CMakeLists.txt b/boards/micoair/h743/src/CMakeLists.txt new file mode 100644 index 0000000000..c47215375d --- /dev/null +++ b/boards/micoair/h743/src/CMakeLists.txt @@ -0,0 +1,68 @@ +############################################################################ +# +# Copyright (c) 2021 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/micoair/h743/src/board_config.h b/boards/micoair/h743/src/board_config.h new file mode 100644 index 0000000000..48ff3ff203 --- /dev/null +++ b/boards/micoair/h743/src/board_config.h @@ -0,0 +1,197 @@ +/**************************************************************************** + * + * 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 /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) +# define GPIO_nLED_GREEN /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN6) +# define GPIO_nLED_BLUE /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ +#define SYSTEM_ADC_BASE STM32_ADC1_BASE +#define ADC1_CH(n) (n) + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +#define PX4_ADC_GPIO \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* PC1 */ GPIO_ADC123_INP11 + + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11) + + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL)) + + +/* Define Battery 1 Voltage Divider and A per V + */ + +// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +// #define BOARD_BATTERY1_A_PER_V (40.0f) +// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 10 +#define DIRECT_INPUT_TIMER_CHANNELS 10 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + + +/* USB OTG FS + * + * PA8 OTG_FS_VBUS VBUS sensing + */ + +#define GPIO_OTGFS_VBUS /* PA8 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN8) + + +/* High-resolution timer */ +#define HRT_TIMER 2 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */ + + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS4" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +/* SD Card */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define FLASH_BASED_PARAMS + +#define BOARD_NUM_IO_TIMERS 4 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/micoair/h743/src/bootloader_main.c b/boards/micoair/h743/src/bootloader_main.c new file mode 100644 index 0000000000..5670308a29 --- /dev/null +++ b/boards/micoair/h743/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/micoair/h743/src/hw_config.h b/boards/micoair/h743/src/hw_config.h new file mode 100644 index 0000000000..a428dd5359 --- /dev/null +++ b/boards/micoair/h743/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1166 +#define BOARD_FLASH_SECTORS (14) +#define BOARD_FLASH_SIZE (16 * 128 * 1024) +#define APP_RESERVATION_SIZE (1 * 128 * 1024) + +#define OSC_FREQ 8 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/micoair/h743/src/i2c.cpp b/boards/micoair/h743/src/i2c.cpp new file mode 100644 index 0000000000..1444ea1172 --- /dev/null +++ b/boards/micoair/h743/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusInternal(2), +}; diff --git a/boards/micoair/h743/src/init.c b/boards/micoair/h743/src/init.c new file mode 100644 index 0000000000..43f86f902d --- /dev/null +++ b/boards/micoair/h743/src/init.c @@ -0,0 +1,203 @@ +/**************************************************************************** + * + * 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 + +# 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))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* configure USB interfaces */ + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + return ret; + } + +#endif + +// 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/micoair/h743/src/led.c b/boards/micoair/h743/src/led.c new file mode 100644 index 0000000000..d7794392db --- /dev/null +++ b/boards/micoair/h743/src/led.c @@ -0,0 +1,114 @@ +/**************************************************************************** + * + * 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/micoair/h743/src/sdio.c b/boards/micoair/h743/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/micoair/h743/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/micoair/h743/src/spi.cpp b/boards/micoair/h743/src/spi.cpp new file mode 100644 index 0000000000..81fdd03f28 --- /dev/null +++ b/boards/micoair/h743/src/spi.cpp @@ -0,0 +1,50 @@ +/**************************************************************************** + * + * 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_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortD, GPIO::Pin5}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortD, GPIO::Pin4}), + initSPIDevice(DRV_IMU_DEVTYPE_BMI270, SPI::CS{GPIO::PortA, GPIO::Pin15}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/micoair/h743/src/timer_config.cpp b/boards/micoair/h743/src/timer_config.cpp new file mode 100644 index 0000000000..515a56928c --- /dev/null +++ b/boards/micoair/h743/src/timer_config.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer3, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + 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::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/micoair/h743/src/usb.c b/boards/micoair/h743/src/usb.c new file mode 100644 index 0000000000..9591784866 --- /dev/null +++ b/boards/micoair/h743/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_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); +}