From 79bfc07c136c4415d95702415a89764d73b1f936 Mon Sep 17 00:00:00 2001 From: jobs Date: Fri, 8 Aug 2025 09:39:46 +0900 Subject: [PATCH] boards: add new NarinFC-H7 --- Makefile | 1 + boards/narinfc/h7/bootloader.px4board | 3 + boards/narinfc/h7/default.px4board | 97 ++++++ .../h7/extras/narinfc_h7_bootloader.bin | Bin 0 -> 43284 bytes boards/narinfc/h7/firmware.prototype | 13 + boards/narinfc/h7/init/rc.board_defaults | 18 ++ boards/narinfc/h7/init/rc.board_sensors | 33 ++ .../h7/nuttx-config/bootloader/defconfig | 90 ++++++ .../narinfc/h7/nuttx-config/include/board.h | 286 ++++++++++++++++++ .../h7/nuttx-config/include/board_dma_map.h | 49 +++ boards/narinfc/h7/nuttx-config/nsh/defconfig | 267 ++++++++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 223 ++++++++++++++ .../narinfc/h7/nuttx-config/scripts/script.ld | 228 ++++++++++++++ boards/narinfc/h7/nuttx-config/test/defconfig | 270 +++++++++++++++++ boards/narinfc/h7/src/CMakeLists.txt | 67 ++++ boards/narinfc/h7/src/board_config.h | 246 +++++++++++++++ boards/narinfc/h7/src/bootloader_main.c | 75 +++++ boards/narinfc/h7/src/hw_config.h | 135 +++++++++ boards/narinfc/h7/src/i2c.cpp | 41 +++ boards/narinfc/h7/src/init.c | 224 ++++++++++++++ boards/narinfc/h7/src/led.c | 111 +++++++ boards/narinfc/h7/src/spi.cpp | 66 ++++ boards/narinfc/h7/src/timer_config.cpp | 84 +++++ boards/narinfc/h7/src/usb.c | 59 ++++ boards/narinfc/h7/test.px4board | 11 + 25 files changed, 2697 insertions(+) create mode 100644 boards/narinfc/h7/bootloader.px4board create mode 100644 boards/narinfc/h7/default.px4board create mode 100755 boards/narinfc/h7/extras/narinfc_h7_bootloader.bin create mode 100644 boards/narinfc/h7/firmware.prototype create mode 100644 boards/narinfc/h7/init/rc.board_defaults create mode 100644 boards/narinfc/h7/init/rc.board_sensors create mode 100644 boards/narinfc/h7/nuttx-config/bootloader/defconfig create mode 100644 boards/narinfc/h7/nuttx-config/include/board.h create mode 100644 boards/narinfc/h7/nuttx-config/include/board_dma_map.h create mode 100644 boards/narinfc/h7/nuttx-config/nsh/defconfig create mode 100644 boards/narinfc/h7/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/narinfc/h7/nuttx-config/scripts/script.ld create mode 100644 boards/narinfc/h7/nuttx-config/test/defconfig create mode 100644 boards/narinfc/h7/src/CMakeLists.txt create mode 100644 boards/narinfc/h7/src/board_config.h create mode 100644 boards/narinfc/h7/src/bootloader_main.c create mode 100644 boards/narinfc/h7/src/hw_config.h create mode 100644 boards/narinfc/h7/src/i2c.cpp create mode 100644 boards/narinfc/h7/src/init.c create mode 100644 boards/narinfc/h7/src/led.c create mode 100644 boards/narinfc/h7/src/spi.cpp create mode 100644 boards/narinfc/h7/src/timer_config.cpp create mode 100644 boards/narinfc/h7/src/usb.c create mode 100644 boards/narinfc/h7/test.px4board diff --git a/Makefile b/Makefile index 7dcacfeb2d..7e45de7b92 100644 --- a/Makefile +++ b/Makefile @@ -347,6 +347,7 @@ bootloaders_update: \ mro_ctrl-zero-h7_bootloader \ mro_ctrl-zero-h7-oem_bootloader \ mro_pixracerpro_bootloader \ + narinfc_h7_bootloader \ px4_fmu-v6c_bootloader \ px4_fmu-v6u_bootloader \ px4_fmu-v6x_bootloader \ diff --git a/boards/narinfc/h7/bootloader.px4board b/boards/narinfc/h7/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/narinfc/h7/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/narinfc/h7/default.px4board b/boards/narinfc/h7/default.px4board new file mode 100644 index 0000000000..c7c30b1a1e --- /dev/null +++ b/boards/narinfc/h7/default.px4board @@ -0,0 +1,97 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y +CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_PCA9685_PWM_OUT=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=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_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_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/narinfc/h7/extras/narinfc_h7_bootloader.bin b/boards/narinfc/h7/extras/narinfc_h7_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..b855256d593e7d19e6d5206ecdbc13263b75f4ee GIT binary patch literal 43284 zcmeFZdw5jU**CoQVP3tqErtzogXcY zyluLu-)6Vb?_=9N146xLAgaD@AfdjxP~b_X&@#<6t>{epThkI#%?iivcGR~MGcgh6 z#nBX3>UZ8;Q%sb)5u&6G5#^3yqC7CvK2Z9r_JOs(Dph(cr_>$Sn-zvVj`WoJ%+>re z*H6F@<@hL3V)5OFqoloHGU{hYCXWkU&eR_uLUqZOrjsg}V;S^VoP(acw~@ck#WXOD z#7YL<^U%~jaNKi`>y&E9G!IsHoYR^sI{9;~S+K z@bo=}H~!1LF>`6jaWyM*3I1*2|NKn$GMRl`wP%*%SuWs7rb9Wf`ZPN{>LrApI$hr$ASFw>7Z z9KhdO;kpc2I{`Dh#B54%pHlT`sSYjY0IAQMfim=&tdh?fa)$h;)Z5W-`x3_>LECOe z+sf(vI^3^2j{GULjN--N81&$M*~GmW_p>ASfLHKdq366*ylk1Y6FXa8^rnd<+U;Z>%jvFX8Kz!nC&WmW=v%TE5+h?i zjjx;v!<|4n-E~|QOea)5pXtK$%p|*0(TCrdTqo4rITV)C1BE@Ix_P2(QbWPM@zZJ- z${-bya=HNbG2VZS^fc1ba}rTnPiB(ygxZ5==ke@3(u+thB31CM5w$4De~xFLBOOFK zI7izeQ#sBs7cpo7lCZr?!>cY@P+Y!vWt;FIne?6eDTlc3em`Qa5`g%&?*SMyX zfClmt>bXJB0~@`}tOQSD{R7^&y~IM_f8M+m(8s*I(e?&W7QMdM%gp^!COKdGKGtc?Z-}P+xNsnxMqq>mdl+IVwz6G_LBDL3EtzB2_$G7yGw~!JO?@IBU zYNoS16#PSYJm|N!maA=_9{Kvwt6y`HrH^5Ho1>kqn|@w5g%`siX zY`?OPS)G-DTy&NJ|Ku1Qd1fcmxZS~iviI`C)fZ%pejd|sS&lqqK3Sdr#noq5!p}ao zGM_}}|Ks1DO~x}O|9^e+Y=TcvUP8>EFmRFNnV>>YUh>R|w{#qCYKdMHD_W(P)^su3 z&Fmn`Wi?x3b`fRENOCK&VtsS(|&VNRF1YEJW^tdv=MB0OAEwoq0Vp_ur ziBsaa<>_1?-?B2Vk<3^5nC*@cKZP(9W3EjtRXnr6k*0zt;xbNM$|RLU`nlTaQ2De5 zKdEfx^C}zHDfQXeSs`CD<^p7Q}wyeO8a)k{NsF#vRLKk*>TP2@t!x3y|_%s z0egP4c)Yls58T;vhzy&lANmtGMuG-$pv>0WE7P4O}z`%C-M7oyDf zBRKo;4DAn}^P6spuZg;7x-Y=9N9BqB{qIJD&k0@Gc!+*a#|>?@Oq3HDN1nx;B*thW z*l-CgjB;>uX6 zKK5pd%C6vY3?JR8ThONwuW3)tNEV$cUu71#em+*0lhk!qSgYuCx)IiKi=E4{6l`th zZ>A7T4*OB$d)Av$t+c(;&+3Gm|9XMk(<^g1fA3OcCg)v$N;T6%az^~sg_OrJMU1lI zC~1$1WzhkwFD5}`6!s{uM7Q0tkg?pd=t(mlsMcDm>spA(h*|sF5N9!%Zz{GtXcKR8 z-Bfzwf+kOE>8<0G_s4E1Hi|!VbBcc?&&9kXiFvoByIG61no**LG0z!J=^WxMdG0)k zu`c+;CV2>_^bO^>40yu3jYZFICW^R+**TW(it!R<_DC91o$~5PYWUt0VwC5G80Fy+jj~ncEm1}Ei_{TK_{+Jf zHk=+(8Rgp1Q8`aqL7Fk=4Vd#sa9sqiNSQEqUwPQE+C-k=(cX_#qeyugX}_?C2>JUWa2gl*`l|7(Fg@SE%#R~N5nx`- zs&3JUv0`c$c-dp%W#3xi(_2HqpNyGB-9n-0O0!+P!A|<$ArALr;JX;VwzbM+GJ<}j z#1r8>+WBIZ&=T7fRkB32*;aVj{tkADw5w3-N|kWAg*IZ=xUR^lBK?NKPxO_3FHkw* zd-&;%;HRPBljBR#UX3eFvU)WoiBe)~>XXdu)U9DEYNzE;{+Z;`x1>sMdlLb7u$9Uk z-|kWKkkLl0Q6Cda($;7|Ep3g+N5rUaW9BtBCv7Fx%l@xrMtOBOAWxM0I?AqYd8|nz zK52{-KfJ)t=9G6-Ui5j1=`VHM)3LkRr(xUW>UwCFW4DKSW1-=7oX6$2QlC8u4jymY5-aqGs(SphbS#&E2S1;j~2Q z!d-0lX|Jr4nv&A^RLbvtRmKcZ&vup zt-}}Pn8so;x&*MlCQ6dZPdnQkyJtS$67-Ru)*UYK7eka1!37^D?UR#;F!MsNlo#Vf zX6J4ZBl7rnSIke<(Y?4lXH-%~j9n_RF*oFwBuMp+N!@y>1G6?>ol~L_N!9{?sQGcw z9`Hxz_AoOOq}SV->CD`0`%=}^#P!$49Se~7>;3<&5__om3-{kpB86ufuQdNwwHcR* zoN>kmy4u{c0i0xR?{RlJG0KmIL&0~)r+~w7%JbkNmIp&Y z-*`D>JM`>V%ngj~H90{lRY>e4S20O&r%GryVf#<6d!v6O_(`Su7R}=4u7?`{ccf4DON`+T6)JI-&&MhGBaH2lDs92< z9M_y=<`gUl_}400azS>feCZu3p8>x8G^b1-sTG;sMlmYDL~+XS@WKKgXnQ&7q!dn0 z%2k-N`U&~}Te=IQEF6l=J$+k#OOh*H>fO#M9LHK&pAi&w5FD5>qE!jq(sF5uYP7jp zd$+$>8G#Y}3F3jmP;lEQW2<+3?PrXt%zzR(rB_wM^OhHhS!nsZnRA&$1Lobq5hE!7 zmnxmp`WAzU$DOPiz5AtZiGy^l2RDlWH>+*|J_mnU%_^tId2t7L{oxVKG#)dVRgR5k ziPddSoN#*Hsthw``R(;v8?q!;F>xh?!Th zj#v)5^T7p((ulTT4H=>(X_eoi98Nh*=Z&&$yk92Du46>`^|8=JV&O~pVuzZiXY&4F z9rlNU;!(;sDZk8b;YGvY4ynnDSw*$8Z|PUDE;2n$V&-x7m?9$CRZCe!H``y8M3Iz+s;=NV(&2yioHPsPwn5S-8_a~|c zZh;ocUYFqGu1oeY*CqS!z0V{?J4xoftGmORAW;&aHRp{PMYYW&-FqLExWAUo(wD&4 zWd0)N0UZy6%hobgdbBANj2pY}KFUu9M?ZJ+cJ7%>tU$^5S_7SmI{+J#>P%-uy^q`#51y-i zAjan^H+antZF6Y-T)@ECS_R-`bBOOTikVVCW|g|om(5gnHH!Id`WEhyy2$$SEvk+y zW|e}_1YNV%SU>9f9?e}-+$S^EFa2%j^>$YI6>y&)4P6;mK2~HV(*#;(l`iNa%p7BG z5L#4d4y~DvIteV)(6_cwSt}p7J)F-8<+lQ6_K6D#bR?D6Mj<0A2S*h-@`XMOH6@hQ zYCt)xk{B|yQn)Q6m*i0JH=#ip^6~shV$?=n%syOTW0gH2CQB#Q(DqZw;9LE)Y`)U0 zwI=$rH}ZiZLb2oaS|y{{dv}#&xrbQxuO`Z!p|G4V<46xpUy!mlqAW_O6!)-VP~1~1 z#{SAAui>G3hu}ZiOf4IE-W+MU`(9~}yGKrw6!}M3r$@YZ6tT*m$BnJGBRxD$vQGM} zlG9x!)w#nX`kfZ?7{xD}S>+ewbkvT?-`@{A;MsxAFVR_+7*GYCZkpdcnt>!Hm+{ zM66G>;AGnWC0jOYtel^R98HwOVasNn^=rR%qhP)0r%(PebY7-1(*)hM8Hk{3VV)++ zx}hvDvzu%BiOTnff&*`^Rag?f8v%`!KHkKGe%>A9u=;tT(3fbY0aPd)88X}02DHD9 z`#r|@@pXTC0xf$S<9l{H_nS|f6JZsM_R-atRbCon8aX%HSg}j zMc-%JH9O}IlKVfan~%Dl8#}EQG_^>sK8@z?)wG25k~R>_X!h71*;PnuAKKEqyWUWc#CiF(`voHjQZ-BOD5{)tC+Vm^`u<8h+@a z1~OzixZZn|yDN!9bcTk4Cy!D-CA6?E#+Zh;w+%(^J(3Y~g$F&JZij^tnmw@yC5hnJ zwcsRd|8cH-V~3L{41wh;FUA_cN>yFB0qbIZ%cIhA*yvIzG^ur@grPM7Be_$0Bg|XA zO9%Ar=b)TpW7MVxdAEm_`47KLsr%9I!n4Zmv43(c(oXBe7&;%5um&zFRoE!wjeEsM zn{2@H@5ZX6_1^0@GA|MHhidGOd@7g1GDwuihUSVCV*MC1N4Oy-w-3^ThK^euEl=Na zd^<0uX(pe(xz!_Od7W7ASbr|C@+|l^QDVaD%*Ii=+UyMD6}@$O@KA6v#fY~Q z!$djoI^}%%n12RHEa2ww2e686j2JIs)r_po`j!*mF_2oXe#I)6j%M13a`#bU(Y3H5 zvx6}iAoI43FnfqaYhsLA<EQFYG!m5mlaxf1*3pU8#OCGd(|G1IIFpC!JyiRuF4VV#f|o*&=g+Km zu*&EN?~be$`Zl!ad#tt`xPsQt+!s^NIg4HQ=HhX3VZpF=x9VF>G`d5#WGOoYmiFrZoTFh zFd6Ms&e;A zS7badc*Wf<-ylKX@#jE;qhIxmX~aicNv;pFa&$n?0C$inL%}_vzskfMf%)&TFXhve zlhlDz$B+g>*KmyL_N$|6#7Y`BLK=B7!U@Z~v?Lw$qu$}W-Rq_O?!!{A`}cAg@GcG| z7xQ9ASOP>TPee+20-Tlv%2=bAJO|pUg;oACO!h<3J!-V2``p8x7ghHcX6e_XKw_h-uOVnMdzahc8iyn*<&mgx&9Me+C$wst`qB^n)_gW8>^%Z56dd-QW_V#S>Li$ovo+q{)}M) zU6{@V`cB^xBe9zfd($^PRD?wzhb*{H|f>fJv2N>6O^(S794?N@eZL zvz)SPoPkzW?9c&b(eOE0i?kSP_F2gKMd;rLSew4amAan@%W(0KB02Z*fPN`=nOI`n z;Na~(^r2&bONzEecWGg@vKVJW--{=VCB@6ZU%X=__^WM5eg@yqyr4P(JB1gcuP2xM zo=VqJ_1ZErlPK?d$ePnS(!PWkUfWYO6nMR|rk(8;L9$}bMV~4qc>-vN^XI~uW zTwK~G3Y;ZN;s=P+kQ}T3dwj>}v~s`!9R$`#3;2 zXMZf$sR|vm9ZXhSUu;~d!o<>6#tv&o4?-T!>)NZC)#>bu<(TX$capDHlhDa4vHYJ% zyonDq6=;=M?P*n*51 z8^o|Z5o;@Hr(-U(@Q@36@K#<)7@6cUNQTx}&{3MSzLgkt%7dd}?)Du%GA_5B7wkIa zzut)Wb*QWugk2$F5%cu*l2&;SdMjic@atQ~C(-h}S_M%7&J)dZywR|h=6Hwi$&pU3 zf#tbLX|qbYz(K7!f{)7V;^ygc10-N;)h;F*A?)@kabw*u=xWDP`RV#RQ`qeS^ka zeEsID{~-9~w?r?T4m>PVZC(NWHGBK+F^Bt`-)50C;oi2L&qrTph5JhTN##XPmC@U~ zy_;t`8Rar$N%)?Z!ft0daUm|RqJr9ybhGNJcoF^9JmPg$9dyKfbi67@B#;WngAb0J zt>VO-g0mH?s+Od!sxV-kAeIrCqc&D!ia61m&_!w$k6Abaa=vFQOVlVIh9=s1>1sQx z(N68vc2+|__~aWKbT!69D^3!VMT_^X?To@Pq2TkO+=47IQ_=A&)BbWH?vDF0A{_jH z)sUNZw49h)*F@iuLuT=z*11z#9a-&jX&<hvO z-hWWmyJk5ga>_gPEzUK($Q?_=7;bS)^`|bhNJ*`9jTH*_2Tqf>FQgYl#Kax|#&*j;N8xZ?oV{F+bKd~}r zR<6C^O+u+td`W|3b8HEX$)+^8mPgFgly2)7ZxezhaTtZk=9uH<7&2M?9N?V*GK8vU0!F1?EhE|#%gZxjW z-^v_1HZE0FI{4^PT(zhik zaq(aK;w(w4E}|93tCGbAwAAXYt7@z?!{fE9&>|W{_{&T~kg@a8PGZuC``4tnDSb?J z?SUL_G^ZDh1)1@lHSkrA7}th^ca6B$3f@p~#mK%j6w6B`%iu4TMtNZmSi01mCGK03 z;7X8U>`89={ti9n-(XJ#orBK4`4tUr*j&cP+7~FEyRWn7 zIh}pAPDUwZoQh{D#>LsY*je+o$D)*i56=HNS3`_Z#auwoG8Vs@UesW>INws!^OZJ} zXc13?N01o7PSk-ALUHUpEjv_0NAhi@eG8|wEwl1dP9NkFT#>r0u#$dLSKpHu%}9O6 z{;fVz!&tN>b#`Jzw2>%UN8Tu{!&$SfzFYg=M!L!}ov_umhk{Q*&YNGu z*1WGR?QFcZkO`=J>=Cqf<%&UL&ApTzXOIL+tHmp4!jmu_-7&0cq&p+ITN z7B9%$<(=!{p~}-)&-o+TAu$FpyE?qBRHvqP8bsMq3Z-9DtGKHs3N%2H3)5?MQ9Jhh?=4xr*vat(AK9$d(@3kl_*MVH5Bnt1u z6Dmv4a%eP0aVxxIMn+i#JBq<;fE8{mcxD`S7RV~q6gS`F4d6DN(I#}pEQIu)->r-7 zJgxHO8sh>`-*l{bCr}@w45>)VuQX4@4$%6lTU<3X{$PbJ_O!Wjd8?%+wP*#CQa)cH zD^toUYE}(w0p(Y>`Rh|4+lGP?ykoufiMK7EmQY}>@s11xmM|{oj%Ciix12GE5q8@- zXTxGk%?f6DxkKR{%TWf6zpMDUrG{9~_^UQ)&8r42=n0gO8IM4{Ux$p5qtyO*&UYEPV>nP>^)h*5%Ui^plmQJqbhs7(H73EX;Ii2|W z`|Qg#OPHnQ7H|ruvctKwEU$#CS;nya&Lo56(T#R)FaNTc(%1GfW4Ltdo4TkIlmx!C9bXsY5wWbsFQ`Qi!pDr)4FLp-odj_@b<9J>J2)M;4=c{ zH5e00D*`U1MN^Ye`ZK0~8K)5E&clDHzkS-Af+HhW2F02rCyljm_MLDt*G;)iXm|D% ztnXjEpoXu}D4b?B!_3^jOzWv58W4#Re*Uhk|duNz4hD zF<-T-Epe4P%(0)g#?;s_o^)oARdic!{CQ!k5uIgr%ra9=imQYB(% zv$?r{e|+?rYf2c)Np+5}9W(Q7bx!_Y<*8!7ocBbII1B4pN^nd266Gqh_$R5a*v)*5IIt7jrBnq zizo1no~lI@Sh<1oX?-Vkjf@+BNqx@JKiH1unL>RZp1r{TXJukSxTlur;aXF z(xZAeSRRNP(G=Olzal1s(i_r!%nhO7)bU;FLpE*T1PN22vXC?0lzwA9o`r((c=v-@ zx|tR{tw-(?|6~{S@DkJHA{y5Z>q;UbX|rO?h*Hi1w?U*o$ubX)uL8HpvYRd2EQ8gM zpLou)g|%4Lg@QMZ+QH3rMWNsbv~mT}69-|(qx9{Y1Uq;f{9C~5Akuu;;&|~t&9>NL zI@dtIPRzxmrDbD5^ALp%+ZVz!jE<-PdVo|GE}zaHM-3;Q)H0_LN7K&MXp5FG3FXjN z5)u&ev%H4xrC9#+FpoqV{u8&#hWwcDjXwl3SV#@~t(}{og(?bXwAz&|9&&l-18WtL zp;GmIV>HJH+$0pdXY3i^k*@n&kv;<~NAeHZfGdn;nkH?MbI`ujvZdk|Ns2pOltCxeFO)c^Pdx#qicJrDTOB;6uT;M+s!&pW3Jwm{T%1#+u`U71~Fvr~M@Rq#u^Z zBo|Os@mlx<+0wo`ZehDSkIF2Tf)!K}ey58jBFls9b)iR(IHM;HNYoXHYoCpP1U;1mmfJqayAccJQOKA z5oQ0tA1Qfm*Y}tE!T3pe#WCi3&Mzu@?TiiY%k1?Q|NG4`$D*S5Z(`>1*~wj>o`<{` zGbuiSFyJ*Dw|@i0pOJf8X3bY*&O9jd=1a21tjKG>c}wN!et8z!H0#j7xii|$gEJ46 z^=Y}ygV~2RUw`YB8HXx1(fD`Pdh4L^kh$cuU%)qny%FOT&ORoI?y;EWGH*+=Q+;R4 zddrs0ayQC|IrQN<)233Csy*}%+;fM13ajnr!O&|A`aSyEo9E1%7UOO3HCp4~Ympk2 z*Cyz4e28Ri9=!OPX=N+&q0e{H!M%A6C+9}6vRdS_m4Jxsx~!u ztI76m)nLRfp*+z1dW${TZc#2&KeXRWc$m_%ubSHS8{9d43IlY8k;F(VlBx{ zJhQ!oF+I76a?vbtf{U`sYs2RyqnDMIR7QKV#T|tvO>}2n@w;KpnpVkqcNG%TW?1?6 z44>65>wMTX^RGw1t0RXb|a zXJ|*F9{amG=Y9ga{C%~*R&RO!D6HRhWmWCpRonfKUH<^A0qFkr zn2h1=0p{sY@XGLu{W0JrpAY{UJcKppi}zv`eGK_W!t3uN8<^dHgf50Pc`V(+jYQQ` zF1{8pl!uqO(j7#ptPKUvj9&Gj|Ef#Jbn2x9_X@!{yIdyMii-wx^Rch1w68E_naUY4 zQu%BjCm0aPoq?#7c_mY@t`w`Rt!k44vrggM)+B$YI>)s9*t4jE%FK@`LQ60xLVS#`D%@)$y!Mo1{&-BVn8R;>F6aV`?$3U`yjZkg z)p$vzWf~C)zlD1q^O)9xHEj4jIYRk9f4Y&3L@Szp5`6~kiN5^Y!?RoWs2Uq>(>A2- zGM)d#lvTj&2nB0Z`i|K}u|s3`Cx|$u1x-{Ft?le%Di_5T2 z0c~>)`98MsuHh#xrJH8-aoV4_m=Sg{_T@;7#XZZVMgzMf=e96@%dC^am{~sZEcopN zPA7eX)0|CDL;G1+w02-Y;=xVOvkbsT9OWI1Qq9coi%WpUWyslZaKp_ywo|as(nlb% z&qtp_!Rtr#;V1dpxK6Io)yg)~=d?}v*r7HDHt1<1o-hQ{NaHMpK)SF(U>Y9tFFO~( z`>Am2Vn+T)rse%+=}&}76-3*9Yh8Z1Fon<(d` z^z`hxs!gm}mG|?TFQ0lfrUYDXu4OO;xkJZMnGl?BE}iF2>=L80(kWPVs$pB`SbEBR z^owuH9{DXX3wzuqk%Nb2SD^;_C$aRxHk9A?fN?aKJI)|}A{6|kO68dW$Yhirs;|ag zcxDhwM1!UpCe@%JmyJYZySPQrHKc5D1xk(RLH`cU#){eNMuTsUJzzA6W^pXINS*2m8L8xUr5U@R zqHx7vzbDcxq(w-JkV;4;r1ePaksd&L0O`9(-;IHd(hUg@a$hp8Ik?hs8M3e+5z&=h zYSpIIpthkY$bRj3@R_0dqVeF< z;s0L_J$_p#_(bS&>>3zcM|~!v!B57w7PBHJLXM4fsO~gIbhyXOZ*O29Am-Q+HaR`- zr>j%$<^vlwkV)(Xkf86YKHbdBu2b){uU0nmx|}+-$bR3(wF3;^>{m;wd;P?ceyx4_ zndS~Pb7hBWOGvkQRHMnG#+q~^Tq2XVQ~kkwot1vE1-ZRy+~V_oVy-BrH1LNIwQNOn zk~!^nE%aFKTC^W=5|q|@-5el39cWJd$+;s}J~}(Wx3^ovQv$r)o%Va47!i*e4ewnbP!3` zUXFTRk0+Ukx(ml}{}pi(|9YR+`tSGESMSwuY{)f;!C9_q0vX&&>E#q*x&`tXGlTBj z-XGBGd}&O9KL5l8W(vjY^U`hZ{Q-e-szU6(fIt?xd$5z!p$c~{RfSv5N_ozupoP1_ zac3(0l1pA^0`c6w%lp>RQmb2THy98#z7Mlzs`z;-cX{8>M}xPHafsD5vgGpK`}YO( zWY0?dY<*tW%58{cqLIov>et} z*F=0FwdL~4TtuJ7Vz&jaln;|E&^nDUQpQzIBG!SAgR)WV3&(b{@GZx*^2*aks|zE( zVvQ(Bv8a2p>PXl0vx!)%Cm*b|cvGYVuTiRXXih!jK7lB9&igTZe5qn1;%}QSd*XE` zxhTXpT1gk;7;P(rAvqDY!^rNTm%tbQ5ZV=vG(zkc-9v;ZqlxJ7PStMeZZ^B$QSI}o zhpxKqcG%Be0IsRzSAhKO!0_J;Wzt`CNvGd0KY4-GCKWWf1@GUbzqk`6yp7ct6ySfk z1P>a^I+wdsMOw!DspV3KPJjB;1y*0{j`DU%@48dM@IryXy;!0iJ;u4%of2MWYk}jo z^VC7*8Yiz9*WUn0;tzH@K7CMB7Vp=R)te!KVvM(M(t3HHRG6cTvy%%uoyP zGW#T5G1i2%{Y1aDa@1><_De52vQM3r8r(77v(g#2MJi8=&x-xXQm`_`y?Bv(x_hD@ zHgUN-6uco+AqnAK=@b{VP}akK8ods?SUa=N3jM=MgV!HxZ17AIQ5xszIH%ujV8jS;FY^dUZIc593~ zueHQYEHomhx-iKdl$YbuVO>Ww@=l`MOn39?_ZE%@8%AtiNcpAQ$;4*XL#@}57)YVz z-=7Pxe?Azx1}y>avjycWuL-e}u&g!HxSz;3G;VU>YTRTf=nnleZZaeL_wd0NLL1~wfUpBaAy`@9Y=g+~ZGW*T_J!*YAd zY|L(=Jfv#EG1l-1VJ7jS4RPhCRmeC~$qb^Hk>dkpgeX(Px#y5Gs5nueY&vY=h(}j# z;2AAyfvr)e>trCgU^kzcFpLXc8s(HNQYK{G>C_sv;~7EHn!dGWvVt zytLXuYy6Y?xy%>bm>TaT*M0GERppF={*^}@r+xjE%hUT-Caa7!wfc%oGSACv6@mY6 z+1By|;>RaZUVi`@qVgATRHAH9vqfeP-QRJ~kOnquqHF_ii~_F{TE>FE1dpR@zJR&= zbn{<@n(CLSf&c|utsC${xi4; z{zrRZQRmT8PWcTalHqQB8>jrE9dpn`S9QiL*qB-;W_L3p!zbE)9okOEnOB}wHDWJ( z4T-QY35eO}lno(nn(j;}m_E))y!Ep0N$Y@bg~Qs)SiW#GJ(g`uo@GmQIA)qxey-x) z8izTHuZd*~tr4=1@;kId13XdtuZrD_mMzprODaRb(Kl(YCyAy?I%Z8{jE(d4N({cD zo`SQ8<>#%6PnDxwn7fq~UN0y`R{|gQW}VB>o+Q?VXD2rc9Kl8Rsy|pngtfRVw-doJ zjqYiN|KnC-9l}0ePSm&T^hOs5h|XkeJKzf@W}}!|9o3^(nT6Pe>>}`j+EbZ)@GKF} z<`L_NA9fcpRb=uKHj?aNzdn`50I&tT=$f{}A^4J1CIfq)(@1vEpO`ut+=;zX)E^ZG zDah7x>H@j_N${|DR@Ong@GPY(a*DGSv)0!3l7scXwbCR8WM;OImyvTGcaY;2Uy$99 zEjlVOV_UGUy~HWYFjB9yv%9EXPGg#2E14g?2zyLgqZdZs7E}7En(H}&-Y^!cn_Abf z0?j+-xO~dFVBqAg!hqZXek2Ml{v6fPa}|5SvBgeg3(J;#b&7N@jebx_30d zB1|n1MCq?P8kioBeH?jggH;Oe!o2Z)M6yi(tU+b=?n$R_*_{C&c&-p_E))yITXPq7 z9SvCHf9Oj>YK*_dcQjy$zt#70z{YhqM_Eg|dNjASvm-)&f#TuW5#3F?o}+=8@m9du z;`{vt3d6IF!0kb{fwtlA{+9y_V8L3~6&)}}7Yvfy?;74VoD3=uAcbm$qk+5QvEw8_ zZLG|!fT)X~7h@j0k(L;SV)zc=3G z&m8ouexbQw(73uoJ{ri0kN5XzmI0S+r=_oVBP{&ZKep5MW{7t=3Y2>ORX|-Ae+Ez_ zu&fTXZg>Gt?u(D|@7ENyqm`>CN+cV8gEtc1xW9QrHqg2}tGD4zbv)aiiF)Z1vY}pn zIdC_6`^%4x1}cF6Kh#DmpK?oK`}u3_`{Hk1D^$L*6<874cZ(DUMPhRMeCR=;Swyjo zdcRy zt{mC&!-9`Qw(-QdQe|e;+lcwIMzzbaUgO;NnynJ898wEa5LDLw&bQ6v={a~x?8rIKrtm8kf1|2z@4=-oxr-fCu^{wuTs zE)dG^rZJvEmwZ-R)XwCclPNCvh8=}G&iu)Nta}9*$q>Jd5evM@ts>tO6$s6>g|TOq zC=7)z73sdfC1=pChu%fh>dXC6ERS=ZC@jBwkK?9x;b5s^6HXZ#RE=kS`V$K{%*OOH zpTl0$8VKFW`L7F?$o=kb3u64gRj1o-uo}Cx$YsJZqzAQ>DzgOUMyo`vIJ*kx%QV&O z+*L@w*6h*w52w=-G&^azuyO2RW^=!L6aAbe^vdoRiBOK~PF$oT6his>EOA!$w02s) z1?Lkzg_M3r@o1IieZt-dKTuSpP46zSN~SZ(gXAtcn#t`8Om`zzhmH~7eSNrvA8DMn9UZVS`($PhrLB?$+uGw^wwX!_sNJc)JyA_chsA7Y zSK)hd4?H={jql2|W)@UM)OA4qK*52#S`!Ud1 z{AGwMCdykL;gx8M8GJc!h)?^xnL;qn5arLFY=wy~SdanE=ecy)Q*cSog69oH^|7## zasF&2Aqpi9r(&#Wq<7rQ=7K~uCD#U9_wPJ8gB>L~iawftor>9L2Sh6Dwp!mYhv(99 z&qyjx)euIS_xEd~!kFxNU)-+&hGI(ldhY+-=~bHNIxU(z+U)}!vv4JlW_xpkO#3_a z`}(VBqmBm3<7p2Ufa|a2&NN5m6m~^f7r@8CDYs28z;ALv!Hv&rq5^!(N7$jxbQ059 z8T@SJr#>^h(4OXw=F4)Xat$AC$r#=m#*`+EDVAc2&GiYdRLN{(+QuJQqx~#&cDBJO zrAoS;48{qzxY5opih=PI;Dhl2=f!%<$8s-X7K#Tuic1Ii^_}4noo=F35?R-F6(0LS zu)HT1h)&re{!J{$|BvL*P}VxcDAlD(vLi026+1H5pAP^)5sEOj93PLhGUYVprjZ za>cZ`m$Sqr!*!QF1`kbyb!J!L-zHjn%dSGl7dA0IyvLF5A3!|dL+K*bJ=5DQScB-? zos8Z4pKr8bUyoUILN zkekHi_uq2=58Pb1bw{p3v;T{(;a|#4Uv)h4`!AhUN4^ptp{1~&&=vkO`S)Mi@$4_* zl7G^PpjAu!bjJAmFK?-O`b+&I#;RB_<{kzI?Dx<1 zPVf6-J(HJO@N3wnuMur7uKzDw!wyZP>kcHdnv(dvu-{c>mepuW*cf4Jo6#u`_0fPX)BIl2i!Z|e8CG? z501-}o`-xUu|!l*jt(^X6v}iJ46OVrtYz6+$Add2`eW0#IV%TXaaulPymwXQ4hQy; zR6e5?>eHaTp17bh6Z5jvt!kkW)-+`jYUa*RpTVl39$3X-+aDsvPh^AG4SN}RooZu~ zfXh(uedtas#e$8V(}LX~_%hf{EVIRI(Ji4o>}Q>ivnD76-38h&J1S>;BN{b}@k5Nj z>)~EstQ(V*F-WR!Lw6@iE$n$*ceIN& zr&jYl){WRf8$Puyziq#681Dmkf2A8%Q1e&vJJ2&eNG6&37Ga^=%`2KA8V3Q|>PAc% zbh;$Ot5-la3iyX*AK>1ldI@YDa%gYB$dxD?(QoE8GJUl%6zs;gx^CtMt;)pk zGcWs@Mq;$MVW|zr`$gSGF_gEFwbFhq9mzx6G=3UaMr~ymR8otD=!Sqw(LjG z;jclTPoO=ltIK@`JIzL+lhS9@_kGCqt0ppCi}Om~*fO=6d$vmzP-~3}-|)UTFHVbb zH5gZ-Xtr>T)Ca;ftn4Wre7HIk>>bxk>$o&jOJN3}^AcsCR+`3VkxO6K zetI5yYD`>0GT}{k!=Duzr(d(&r!sF^Rdgl%KY;(0MT(q09kTchyy8}QlXi#pKqz>A zJa^`xALlPlr)9qrF8iHYu92SD!a=WUuVpNd=VMqSFl*!CbHT1EwHy>+#!gxLvG8-k zW8W;s#kSuuqYJWnCXL?&yq#;nnAo|-AC^SQOWKGN;$|eZ-U>QMs-Ax-kz-BT1FxzE zScUeFn`NwWaye#iOn`~ulwjy@nE$*Ir7||Vvb2_;^MO1Yt-Ldgjdit?aVC&mSyO9G zLEZZ84suDVg?)E3xwN{Lt~txZmmSIeckuaXf0w&eqNf(5R@i$v<&6;JKJSVj0gWb4)_C_XW>7%3SS+DC+o}3 zQ9gPT;1_kj(>!fvNf&L;0^Bd~l@9u);(aiQIeR*SZ=P%=KUE+U2;>|EapG zi9#&si;2P6RLYU@2>hSM%NN`__{3|V>ZFEqk$F3HOz}RFKFLohU3-8vMJWBcvDL<~ zd|3*=ejA-@X&pDDX2Ag%mFTaRLr=%t%>uW3C^O#TIGsgNU{X%jO3Jk!;^}QZVqueI9teTpwh+cm_<&LLCSHn$|^`N zn(i#OQKFXC@!<5M`EBLcKh zKNIJoWwOd#l*onGWa{6Dav9wQX*@VI#F!ydF-AbF8e+1(f@Z5jgeEP6)}8Bw`uN!^Ky zDn%=LTs6!#!Wu4G249CC-NvyE>AN`F3MtC3d1438wISS=N4-ALDp_bXwEBrb^Y;fpXl6=@t zy{-Wk=+Y|;(i#5Y;Ehy@5HoOkg-BmNLW52x^qi1Ou_%kwci+3K5dM>_ zppV|KxR;(br?(plsV21GNnUIknqjLKXExJQ4{$E<4F?@v?PU7?C({s19PO)ka%S_s zd#Nu7G5nspw?_0INIg~?PC8H62Ja=#uAyfnJdPNW$XC<+XE(A+DC%r0W7>y0S61)5 z7gnf1D)#i@NMtLidJ&n37pBpkq>1ugYLfHto<7Q(c~SP zCvS%}w>rraJ{#}ONvfi2o_#8%Ik9=0W14SO6_dB* z&a~zuL$md}DNZbw$9kot!Jf?;Uv!SnpQPC14egW6VOh}HAy2{?-_!?SXpcrrB$?Un zr@Wt7T|S(3S2kI(Yl`XVP}@8-?gluc-cpLQeN|LGq?p)Qxufv2r_8^MLJOXDTR59lN>MCRRBT#v+x9dp8oqR6cx&rke*h9Rfx*4~H@MrA)v4 zCrLb^FV=K7hm58rd< zQr<(b`>0i|hpTMxiS8=o;h&*rEm7`p5a$d~9{_#V7=CxSiaWDHvH|}W<;F?|de5#x z3Vl=cIoejf7yncE9y!<&hnN7njs(gyKUR6ylQ`>RAEH+bTpspB?RUH2@i$hE2mdfc zDU$uzh?%ir_>kkgpY8;w+FzX%Cr%bAy-XAAXiLVhZrW|#WM(ORNp_Z4mZ)bOzEpg zj8NFL_Vt*n3^&!uD%TD7Zfx)_Pz;*L-jd&hCgBVs-g+F~C`8KZ*00p`JRoTlUegJR zx#*`YOdie$w$!@yh|9U+o9cdGC1UF@(l~lb{ZyCzNu`KL1&gp-h1VBoukN#&6V_Ff$E}r9 zU{&nG85fhXHU3nc<}|fmogTX&M`wf1l}yA%P6F?zGE1~ckwN1|uXwO3OWdN^g~of| z{eK$!7PzR&y#MFSnHwEf*9l~V1RJ66PLtg}?7`OoKb<~ip) z&w0*sp6l=VUB167&RF8&g7@Od70jJK&o2`BMSgArrZ{uV_NA*p0?2ryZXn0pbl$C+Le@)s?1TPr1yfp%8;*S zz#lDzt}|fS3XY8&7mIU+#Gq}98A3e-T6F=~#9A=l_4}^}LunFW{pt%cV;;VuxsNyx z3ZJXbj5Z0aC-~lc&NsUCFQGM9pgnuuKts(`7s*i*Sc8LB5ryyA;Se^J67eYmW#RZZ zRu+!`J>p^GA0CC6dn>QB{PEheYX-Id@!B(Mj$eMq`P#K-R;kk2Oa-Cau^w*&D8!!j zSM5)uCkAsG>`!^A?ubWBcGIzp?7d&MMY;b7YwvG8Eb|=r!smcJVlM3x%Sx*-C$&TJ zoo+W*Rsrpx%f8eb;sM>d%(dvFCmb7EV$l~&{be;~7p?gf4$k*xu%RaXX3yb#d&4CU z$>^Ce4wl{L&>N{|alWsB{6amP^PQH@GH~`ebPN)~8Khpv`95oGaK5sj z88nv~$f0HjU9W&`Hfq91qs-_a8X#R<0@OiJc%@WRKlbArZegQG={vASnIDgDk?AFz zhqPkpsb9mgGw6Rc_?fq$G6r9(a7PxtU<0oQJjk`EYvtLf8a|zO$Kl{6bbBLlUxNb{ z*2zjCOIW(;?WP;^gWmH~A5nrTVMME7UbzIkQPL<3`scqZmj?G($`9@awECWh;+ytX zeSGgc&{GZa+C->iJ8TVg?9A(R+{FL&N`!En|G~3tTqAn65_H{R;U-N---eoCDOv8Z z&rNE2+hzbwh!s>=g1emQS&3(Zx_OSi@%iA}HmC5N``okK7zil(Lx@2|+}r zECjpj17`~6xpe_(#@JI@a-bKM0nIRKQv)=BoZ@EW8snn*Z2P;gpfWnepnvPTv`4sg zkN9x;Cg{Hm=`TJAJA2C>lVTh(I~?tfxD|_6w66dLf@AT@ zF)Jg@+ER<~sgpBDt;iAMQNxI_{MbbN7{W3j>rDxie-yinQAOxni(GfPw9uRGhYmaG zUsF${eNyan8Yfh4rLYBv0#0dxKIp#~DfRPq@Gp$5*;vmSxXSk{Tjs&w|efvi5 zH_KCjVVWXqi9_%Ffj!kmmx#LDj{F)P9E-Kbq9J+o-=rV(MwcC!2AhH(NZ(UAh_a^P<(k91aEuopth?erCBTWJn`fm1M6l!#X2OLi*fxq;mevXsZ&cYsfP0$TIw;#R3qpD6O?e4t}A zPVaocf?dQ=Wh!Whp#RBWX=k0CGtt|(N{5h65l&}7E*IQ&(D)0*9hT!7r`vJ=D^Qt# zS1YeQ^K0Vd)!AKw)krn*>VU(}Ql`3JleCTMQr)D5k~U*>$-<&j_DddR_xoz>#UkxS z`jX8^nRifKI%4K3Xh))!HimW&M9b6e0X4)~@b!BF_+rETy&JD^+31}H+FfWT{i3J? zIH>nlCZNBk2)n047n$ak=h5qwFM4|_nf9AiOk3~>(-Jzua6t>LqDq08neSYmSxm!u zJnT-lO(zKq(V$oIL%lFs*a-9o2A*bkEc^d3z{Xz(rg6T9!6(5>eCP5Z0tb%Psh}z` zr{mk@3M033E9!{8>0{hW?J!kO5a?dEKsC~edt*Avszd$eYpKxrlAU_apCz4>`ZbLo zmEdS091`6mF6UhvVTAnXp&cG@D=;3K`u-%#EFKy-h_!9Fs?kf|M!k2iFr>x}`;8$! zyKX^!n^ZG*bN%1ypYY7DQBNhx<1aGh!GDrJrEKOY@a~h`e0sW@BOa_XLj?D-j{(KO z481mG{AL@xImGvP6!k+5an42?C_Fw@*xzaq(pUW8tPw*cWhoKu%v@Eg?$ma_#HApQ z70?UxLfgz&n<{Ru0T(#{J-<||?>Xl;P1L{c3SRO$as9Lt`U=tlL!5&%{ME~){>FnV z3zz;lc9Xj;+iVJGg>18}^so#Eb_?K1_ak0UXBMn@fArR-mdj7Dbo)O&u@FxzKwn63 zobh$mv1qgp-&=}Iet350&HSBP1lgbS{R;>3L zQzv>f<8vsTVY4mEQviL}kC1jp{eGm|`FOolZfTQ5%-V5>aSS27gCK{YxNBAME$2us^3^(I1!C6 z&)B!vi?Z$~!5irHcViZ~4>`^Udd(7qb1=5HMt&}BotxQ0yH(n8qD9s}B&KiBiz7G0 z7Gec61mm#g<+L{KY}x{eE5?G!_}p)sBAPbZVm&5s5w?JbKr0;w4gxoYbTCKAYu&Qm zKiT5j=3*=cdP2LshTuouKiU3%`uk_~lHxd*U0OA%iIddFM`1tt&AOd3XJMoKj?cX5 z8xjl0*P?7FXQSIJC}w_SECwBu-1mm}Ec!9w^V|!3o`@V^EBG!thn^v-n9lb*U7(hs z8|n<9_l%dZdlnP5tolu7_0_p{u8>dlxACdhWLr*!YUrrF53uBFcp70ouk&-*zsA@P zNlPtToLkX;TUPks?~3`_akU6B=P|0VUct(NFtMuMp}4;|&xtXh3g?3=JZ0Z1m09?M z|Bel`6xcwDR9zSwh&X{;kaqDuAp~u)5K!pPFrt}o3&@Gsk z7aN+oPOaJJX6dmVw2JP~4E>z!N#v42f??>xF3fBY_DPFz)jhzO>(KIK3B{6OGhwFt zTcvv~Pq^r5ST{jRLpv&3hl75uk24ec%@PaH5R*HJB6ng(@h{#zjMz~`VCT8rrp1oJ zh#f^l(~`J9H<9LkmDl*(cZemrD6?rs{N?|U#~$n^LV3_`Vh?r&XS{nhRp1`&CNe|2 ziCet86uZjMbF`Z%#dGv-ZfdKybknOhpPmtaRi61k<^M-~se4?TQ8O{nlyxEmzR zSt#2qrw?3`IU7HZnGrzhx!(dYAOV`Tb)vQsHGT_P+|?6liRoTGSm)l@!q;N#a{c~H z$UuXBHgE&8lhy-T=NDSw)eIC9oEiL{moWBbFFU6Rs5YjTLs_}Zqu4^3)%@jlyvy+p;^ z2`Bisw!L)w~PC*7bWpgK)Rey3UynNNW41lHRdVQj+%%!%%Py zS;{W=XWo3*@haPE78Y;gm4|-f)XV9;X17OYC{xL4pFv52R5Vb%`HSN zkPXP)tq!1$V$PlOd}ES{bZ1oinX$)T5r74}RtY&J59|gmqTuo(!)KD-sowJ0dF>mY zosWE`4|w59ArF*PluGT&1)UX=pcGu5l}`J;msE>|9)EsdP`6%JC*AFM=ZC>;@CTv) zmww>cd*;NM>k!sS_gl1Py-~zCEw{|MI${;Z?(VXuL0jR>zPYT-cD=K#PU1J8t5aTE zvZ`U}kP;yI}bXwyA<{Cg+>qNAigQ|4dLFW+T$z(CIt6|PK4$IQ!o2`PNiST=k%?N7$^FzC~b5-#1#<#-&5>}|FY4(SX_ znRCI)x3wzF+Y)&5@uo6|!J+Qt%}PUwBf_k8Y;=6&a2!+3KIQr{ZIGY;PLiNk7&ToGw{ zW`(ZvM*PXj`W4SO6yZ2#nz@4T%WlNJSox77^fWz5v7G5^tkD-`9y0A?h%>X^iPjyP zG!8vOtHr474m!=8QDK_ni-_LsIJbfUV*j-josKy^z3#P@Dnp&bI+r?3D@s?GSJp`p zomJ2x8Gamk)VgyknR)l>?;oj?;&83ebv{}rB|6QkN>}Y&_3bL->ax{dAcpLDWZa`m zA078t>0{M+(r|omVVz`T-p8sd>m;*tjxSRCpl^+)PD-}aNn@RLlF4BmS0|0@tdo)) zbyA9bIi5ZGYiaXV5>)8B#h(^pFIN$5g;vkLwfPZTX^VwRY=C$x8 zL3FkGlrc24p(ZWq@sM%#xwdbLyMf3r0l0|mj zjhH^a0v;^5iOn|esR!+^IhcX=mm}e&g?N5_uyUYX?z$Ron&zZk?DKbFh9*u!ufMY8 z56m&POl-TyQmDU!`4W3abnBr3On3VHUk1LD_fX_3sa_ZMQV!iB8n{y}?@7$5?D~{a8RjqI3-7n%%(4V$FW)>X7S7t?XB6X) z_B5xUrNrgxv$Yv#JqF6YY=l<$Rn4I=lf}{%I^6)XoH~tMA(w6&;LZ}mCIp*4sC!WKQ(reoL{PsR3DpO#0lXAsvwXqavM3^h==GrcAJ@_{y$2>X^ zS|I!QEYIBz3#qK3EwHU~T=r(A^}1mnlYSL)Q@)t6MQ_@{LWcYU_~^_` zyT1`aj9pPv-^kL6+|No07Wir4x&5D==W{-TcRc2s1>LoY?c6J8&+`lNP)Cy_zQ!r! z38$bncPLm)E0=Y|u6?!BTva0M?+QfwbeivyzXhk2u6Nt7gQ@`sB;}lY z;>|Qb3$mZRnS$D054#VN2>;E?)$jte7cCQ9S*a522e|A}HCd^>?pR2EC2+P>LR?K& zn$|sT<}k~+8JzFDR0X+EzB}EXT#_OthUdBvl# z=yS^Mkz4`U9Q_qFn?=~wgFTV1thAAyp#RT7zUHXw+y=r$;M0e>8^p0#38Okqh*!9` z7O75sdzvLto+jaxw@e%-BnUu=5kAAg%%9*3qC&XQ{KsCB+i%8tL-h{dZz%VFxpKjG zC>M3E-Poy-?&Ng%mO$BZP_`W6#pS}Y9i>$YQQ$q?;hI!A9!H|95%kQUc3AjkLVBJV z=}so;Iq(>liZO*OUFs;a+eMNM-_0(*2&)m6y2L%yrydNNP0j7+UKrM@-wEl-T1-;Yt&kLw`x0$)FY7ODTN{6ALI!KFlOHBRc{l~`-b&I zb_T+2rT0v&Ob~Nh)Z2Eq5Kl+$mFrV4X!&^p<+6MF8TdP@92zhlFd-=g-F!qbhU)5(0xgQz*^sVerf-v<2~Q9d0sI-!HLMYZ$nc?EQ{`umiL zigv|*_?-eLmwfa^9~#-LdJ{6#cxr*Rn>9VR_r|P3^se5@!)8-|h!^X`4rp-R>oQlC zxOR$DU9cQ0iIr=X&Zv&HkXroIrumpJernUNZqcUkH{XQTKBN@)X|!Lg6_>c;@rI87 z^9|gK_qg~sfG+S)?>H;JgZf*qJX2n{`Ay&V-1sK_G1s;HHQMGAqRMj*P-@XOvNi@u zRH#RP0DiPi0M{pVq1%|Y;Pi=bt3`SE%1G$gEs>>ug;+C8m|IubZJlo*?Hz8TDRzQA zq0fH}9*y~=cWnYA83tA;@=)o3 z-e$&I%e5*N`nwZv+LU1g^)GSIH9FT zd4{a9x;s|e|KUxqIE{+tadle@5&y`y15U-(*u{LYb_LMB>Wkg2J6sjgM}Mq8-;H+A3XEW zu!Bpgz}tY;0%oy9XdCSuZRd7TK21TeZIqukmeK)gR~!Rd0EV zfLchj4eb<1!dP;@o+=&ZS}_cqvkdc}LSgrf-kY@Z4}s~5G(G4gt( zM9;FK-}DA|k@UxhJh`bzI(?Uj_3}7;9vP>!aEAHz5s#(Y$2=A%l)>^O%0Azo z_?YCK4^J#19C~_x=({rTRiS(2uf*(%6&rh65cXIS1bzMdq;yfakN=rcNe4c6mjYi)zT9ZzCC{)NCq1c$V|#~%~+;m8c%dXs>V zK&3njUPBw|fha4YVaShGz`rO|F4*dj+>tPfCCpqX*)2Fu>Gg5Sh|kmEn=AT@kW^3d zAAzSaNb57MoaJt(@%mygsp*0@!+FUIxl|(Pla4W|BikhZZ?Q5e!FR8Oy%3xGEVR?% z-^Rdg>G4m&>_G7}4-($aO|ZJgyNl z)m%sTozzFDf2z>$;DKxnt-i<61Ia7kjeh8WR@<#xt;b)2+5g9;-7du%9X#e_>jQqJ z?2(c7a@iP@UrXO?gxmoL-o%-c{9BHZ99ho&82K3bzurr`AsuMFZSa4>Ql_|B+GICN zo%kO#qYA_*jFUNmF*CT_<@RXt1FYYP*nI~4Rs9*A79j^7W4DX*V!1Cyi4$7(+J>DO zC8oCQi;J0Y5f(#Hg3ntoDhfkq(KE@%b8)Y}llsum&h6sMw!K}PVqcd+xu;9XZMXmE zQOzK_!qWSeJ*0z09&8}lm3=P_g06D`d^fRV?zSCvvls*F5%wi#X;&KX7xZIZL2Rw; z*{MJ*vLA<3yvs|^Ld&&au>8GK-8OLyENv#=@ZS9|K03da%F!RLH^J`HiJ7dQ{Gd?( z$dmNlQG=C&+CzL%qPB^q^{rhG-9svIZx5aTF5eUZmfVWXwr5(8$1#Jokomsup(jYA zaX2&@S!?j)9aBlaOR+|s7U{8G4w`m@yT01wganP56c6;ANQ(dPQ>s& z+I>W-ffNet=O5+y?oNz3_Q{T^H1@uD1~?Gl9T>y9&9K>m%}8ewGihd&l@2!SEtUM! zdNk(226HK`dw&0scZ2hw9J(>&-?u2%P@{FdWn-SaV_YsAhX=2FZ|JszXL6XZut*oc z32G}^Ft(6~2x(3L>-o@@fZq~`?NoG+vA8hK61MHujZFKf0+&o2b$Mb#AnMM#dLI<1Ur*A$DhTG_Z?N)e6|8Vz**7PM+b z=*|}|DOz#ru@Hmg5_gnt#Es!-|;|gr{b}!|$u-7Qp z(^v4h!BXzLD*j=DK>7OpIRg_AQvj@+`@FtGIxz}7#X+Mg#g8?kK99ZUi}Q++DTOUS zsrpg;%syJ&9-DB_@8gmScg>v%+@wNr=OQJ(KcS$|ZV`O%1pH}72%j9NCa1Q??u&a# zPPG%5%N$>2zvT736S6Cu(rc~K9wS^OzNJ`3RN`fB>`-y2jL*b*0{;FZgy0lwCqF@0 zC01?@uNhHxMaiN9^3CR$9$F^~fDEP*wKGqT{4SuF5DV{cnwiIAZ;Tz#)x8F!mNA{t zzp0$m;o>_M&5`LC8G_G)Qv@iFW zdZONp+^zr?P{1$tN66_2C63}UdVJWqJ=Zu4^M+bb?&pCQWa=@Y$13*+{CD+hfSsTR zEgtauu~yoVBew&nD?SMbOR0huY3}ULwMS!DPnHwCUf2M`4woIC3=Ru+GcRsF$RTw) zXW)Ai=cC$GVrvv^uy(TkR)H3UnEyFum@@~Tfd3c3yg{+mh`rr4(S`Y3;xgWZ9vxOuJFVYXsS4J?SL85ybIM#dz4?;F?Hp5+ znT7Xe#mes`%{Ar|Bvs;22s;1nOUbi$U~irjAR+QiuOOR`PtMd%Qo_vXST?R$Awb6l*d zjE~y_pI0$JsY(zc&!$(JgxEqqe7kpvX_d@qF6^><7SJvU{)wT}r_q!B5B62T8@^oC zCERViU0q@;EwHOf)?#mR{5(G)%0cwWv=^9m5DvmBIsyCC6Br3RaE^F69bK{3--P2M zQzOr0r6iusnow(t@7N6-9nPR|#UM>mYRnnBj!3_9+Mc31yAUZNk>YOtN3RvvlW?uT z^<@4#NRDD5_jiEqRf*%Ft7t(TRe~ogdB&oKfZ(<{;I9vGmR|o(>}vJ!wH)x@3p$Ui zoPrm*nXthG&Y=(MD$zIfpl^_>vj0x&ca)!$ai#f z$IZ-B9a)0fHCeU`_tomK;{v`?O)LGb^A& za+sN{mxm+o(!;*y_3-U3TUv`O>zD4Sl_y%Pmj~tSvJE=Z48Buz$E(-!ABo6}giKN8 zON)?yBTQqhmj}<^Wy_GYq&1yOz$HHC&IZ4RG=9Hw%d!G-k}DhD;|hTOiG7~^s@IIO z9xrICtIo1(2+at)y*Idwr`;34tCagYz9swcROIswx_$}81~LN zPVynBWgmN^4?Whb`91f>FC}Fa`|kn&udokScff}M<_Xd)y|HVUCf(qu5k=*Yxr8C) zt&d&$7A@pgm_4!2y#{`IPlpm7%8A}GNV`Qt%eNa8;2ZF1KYElh-8fw4Yz}AWPpyZ+ zht@W$;8hQ}cCerRx|bvlet#MK3r<)^v;yr=0{;7YOB2&$!5fE6AqALQ*d0NhaNYYv z%gPp(`YzfD^H)A}xLR3C0_JO$PctL)ebe&$ZmsU&^UD8asSzD4J+6cKs-?4%vJ?A# zGvU)&ZG@%5(&G`c^k*@l`}1sNT?M>jdMISRyZ$Z3PjLl5i@WjM{Fa$0U#L_l(S%T` ze*06Yd?`PBidM4sUVP=psH*&nBY_wZwPf5Sb=5nUKCC)?NhsNOspyHmOaJr4h)epo zk(V|{()gBr5iGD}bl21cC2{Q`AB)4kmmc{-ts=hfXoi_an{9^ zq8yyzWr1aOx{>x5XT6G+;8*lrEY0eB(YdEf$Kgw+;~NIJu?8KOH&--)m?72+Tz+(b z_to39_!f>M^d-f~dgS`4vp|TzcOa!t6VMMSyucO0Yw*BpMU+zhjtPpBuYtZi>eLGR zx}ufV3%vCu?}yz6%|WZFSJOA^0MIEaJyer37|vaR9-!J%Ng@KVatXA7 zXp}(FtG*m1mqObeyv^yWch;kh);afgE3~DBp|bS&B0^=!XMyN}=j5_*9O^W8*~#aM z9y+baD=oBM&{}r~6kGRnMRR*>9|^As3s22=-{(4rT}>(OalIP93FYXvjwwK0tzctA z^@_IV+pN^`M)*E`!O9ifsIh~gI+zp%zozN}y!raeHf68kD%Awf0XT@c68OkZ8zlcOa6;(%eW@)M9G6zY_l3^70an>PYM?&<+R-5{ zDqy}hdYJEYPsnbw6_~n>;P28t=1bgf1%d_x-U97r$*yw?@M;GG`JW}pJWqslK2H<) zfTwM|0z4ySgzjE-%6Cw5l!LJ#r)@@=?Lctso#W%|q5LNup*Oz| zy&Q^3_*u+|Bf!f%g8h^knA(GYvj7}%cQ$(8)x{S29V!qi(KM7cp zkR%^t-N@}4()tb_U8_-fe!A|0ziyNW2iD>+uZ`*1z2*{Ma~wE?rjqxrM5%}B#?&to z-?feYb-MeN4ex>{#Tj(TssPJbB#!=d{$-xu0b2yyWe#B?Lb^_H=gZgH*2T$76QhK} z#7H2fj64Y$aP^{u|7yudddimI;7)H#xX)pY^MNDwh4-H1^WH_tUhl%>@34Xc1991R z;6?lcYXX(&INAlhZZ5m_yxuL5KRJ{+MFH&?r5oR1R1{0t3o;{D-0NK*rDRXz;8H+& zBL$BX6u;&u_b>6h(}%>&LS?jGqM3wk7@;<~@NKe?FshC#C_386k< zhDCj}C)pQNn7|W>0FN*+Q{6^=nvE?gc*~a8nju7B4D{m(d&{pdoxRpiIlj<8sAR~@ z42-=vjp_rkp+ADP`%@gm&s|hNz184bV_j5A%`KpO`Ar@^cD`-e%)_iYb$$=I!8H?QgYydD3lFZh{@?TYUD>;iGI-7($F zJy@g=B8zLq7i@eRcg;EE1zTjBM!r^sueX6Z35`3}dIsN)VkH?44HB&45a{ry6hfZ5 z@;*fU?DE3}!$t>_e zfkXt?=-wf%AQkJ9a4G#F<2ZAzj#D^+-u_Fok-$bfKNVONKRC1~hfciS%Z~R$0 zU}E11Ee#>^B)jHhR_sQe4=O61;?6kMRiM{~>n)UO&`Cnyf!=kuLBZ8;$W$);IDR;0q-d2l;bJwz3^rg^jBi9G508RQc!zzeOJ&7TAiMw ztC@0|yYN5Yzr8QxD7}AdP4 z67+vR&{mY~rasYnrTY1MB*X0_SG-3`K&V6*i%^Sj7(yLFJwiP~9l~J|W)S|&!orkZ-%@#>M-WhqdX6n9_%6l)GM4U@0-ful(G;B^MOYxr0Q$hd9K zYhl4l@rr$J>E#8fi?y%)}R^luHXX8ChIE%$us^>D!hT$y9lU;c?O1#51 z#KNgoGEdphnAaRa;TJ%9>b(x75$Ir=kHq}+mk3&q+6|2{a$XR zw`smMs!BYPE>m%}b7>4bd+Mgq_YYvMQ?g!FiYbVB=?lmSRkP^({IFk4VT7TrC@Hh+ zk6k7GBw#l&AiEn(+GdjKW%U_=9l~T>htV?)@DQbMULd|?OLl+$Py@b)Gp9h>3cb)P zPbp(sZa+G_#JzMk{2RcJfqsnVY71}%)8ail9s-}o&3C6jo*wl7H8>Y5I=&|tGH}d6 zSj){o^MW3Lsu8dIQT#N9JWGNiZNv@*$S-20^l%y>j z-xjuM9jtQYiYy%WKeD`{#!*qWx}v;t z)k?hn_T|;fOCPSdgVFnrjRG!IIOM~j8WDSNUxRB3wYc7eFftq;fopm$DtxUAhl9f5 zs*06m)yr?Y%}_LN-kf>28SvTWJohLz#hQbxCUJp5+#+eJ)?LyJR)Lyuz^j#wNCI1D(FaHJ>}WtCSv znzefMnMr7-Q6IELW-54blPVKR>U!pE*m z@TaLmpDZWykUCnDX$6%V7Ey+`TjmyLtky#xof z`*IxA?oZ=T;`l8N>VF^MP~*rzV(JHrkeFW9h(r+xsdG?&u;YUI!SSJ>7Z5s=8KZtc zFNmfP8A9^G*f)5u9^rc&Q&3pPGoC_Zq(o@gqhTt#{zS{v6zZdy2BFMLrt7UkSOh}* zIcNbRbk-%ZD1^I{$1)wl;~!?SK?pk^oXDaPvWRJHFv7~^53uE>%UQ~DG<+)BM#g8H zP!Pgv?6WbpIr05>K168!?j_5M2-)7ParaU9!=uIHC^X!^`*J=)R`J;}Ijs9~y&SrS z&X+@!MGo0RKUgUpt3MbDt!qLdn-LC&S$AxwU(20O410U}H@~jCGqWI}>)T0jciy(i z^6hhv7v1sBhPK}|oqXx`oY(h%VZJ_N%Cy(77WNN*HG9|ZHvLt5WJz*C^;_jB>W`@E z@k_GG0lOy@)}N5Wx-Wm1ANtPxf|1Kr&CQ3m2-kYmr4%tRbr#~_{Uk!4kE;hb4>X665)km2hLwpoT> zlwyJr3Jk@Q*-&&p1sc0-!Yl?qAPSxfUi`X-Y3ZOm{u&OGS7jxyLfK9~#k7yqGVMWU zDE=tUe-}Qd^jSaEQEtY>$&)PMn!;3o&$F=k3ufnJ-x>OaE{Z2F$$fI-ec^e6_67>3 zX~aNi9D7?tqw~k$8jdpl|N3Qc`*fl8fkx;o$bm0HKNXMOoNN9m8$R?6GzRaci0E+| z@{hj!$p}`7gMJ}A(_rvP(DqK`LuH|R6!-HV-QPy^fB5$bO&;N2XZQo!5Pv7`%|+aI b;d6?TqYZ2xPH#Rh-!sxZy;i>IWbFR|LDuQm literal 0 HcmV?d00001 diff --git a/boards/narinfc/h7/firmware.prototype b/boards/narinfc/h7/firmware.prototype new file mode 100644 index 0000000000..a5410f8e1d --- /dev/null +++ b/boards/narinfc/h7/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1183, + "magic": "NarinFC-H7", + "description": "Firmware for the NarinFC H7 board", + "image": "", + "build_time": 0, + "summary": "NarinFC-H7", + "version": "1.0.0", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/narinfc/h7/init/rc.board_defaults b/boards/narinfc/h7/init/rc.board_defaults new file mode 100644 index 0000000000..c6235b2523 --- /dev/null +++ b/boards/narinfc/h7/init/rc.board_defaults @@ -0,0 +1,18 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +param set-default BAT1_V_DIV 18 +param set-default BAT2_V_DIV 18 + +param set-default BAT1_A_PER_V 24 +param set-default BAT2_A_PER_V 24 + +# Enable IMU thermal control +param set-default SENS_EN_THERMAL 1 + +param set-default SENS_TEMP_ID 6946850 + +rgbled_pwm start +safety_button start diff --git a/boards/narinfc/h7/init/rc.board_sensors b/boards/narinfc/h7/init/rc.board_sensors new file mode 100644 index 0000000000..4615fb8aee --- /dev/null +++ b/boards/narinfc/h7/init/rc.board_sensors @@ -0,0 +1,33 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ +board_adc start + +# SPI1 +rm3100 -s -b 1 start +if ! icm20689 -s -b 1 -R 2 -q start +then + adis16470 -s -b 1 -R 2 start +fi + +# SPI2 +rm3100 -s -b 2 start + +# SPI4 +bmi088 -s -b 4 -A -R 2 start +if ! bmi088 -s -b 4 -G -R 2 start +then + icm42688p -R 2 -s start +fi +ms5611 -s -b 4 start + +# SPI6 +if ! icm20649 -s -b 6 -R 2 start +then + icm20689 -s -b 6 -R 2 start +fi +ms5611 -s -b 6 start + +# External compass on GPS1/I2C1: standard CUAV GPS/compass puck (with lights, safety button, and buzzer) +ist8310 -X -b 1 -R 10 start diff --git a/boards/narinfc/h7/nuttx-config/bootloader/defconfig b/boards/narinfc/h7/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..111c93fcc7 --- /dev/null +++ b/boards/narinfc/h7/nuttx-config/bootloader/defconfig @@ -0,0 +1,90 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/narinfc/h7/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="PX4 NarinFC-H7" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743XI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004c +CONFIG_CDCACM_PRODUCTSTR="PX4 BL NarinFC H7" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="VOLOLAND" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_USART6=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/narinfc/h7/nuttx-config/include/board.h b/boards/narinfc/h7/nuttx-config/include/board.h new file mode 100644 index 0000000000..9aaf12fcda --- /dev/null +++ b/boards/narinfc/h7/nuttx-config/include/board.h @@ -0,0 +1,286 @@ +/************************************************************************************ + * nuttx-config/include/board.h + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#pragma once + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/* Clocking *************************************************************************/ +/* The board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 0 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_4_8_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * Note: look at Table 54 in ST Manual + */ +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */ +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */ +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */ +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */ +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */ +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */ +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 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 */ +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* UART/USART */ +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */ +#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */ +#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */ +#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */ +#define GPIO_USART6_CTS GPIO_USART6_CTS_NSS_2 /* PG15 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#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 */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PH13 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI */ +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_3) /* PG11 */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */ + +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ + +#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_2) /* PE2 */ +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */ + +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */ + +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */ +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */ + +/* I2C */ +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ diff --git a/boards/narinfc/h7/nuttx-config/include/board_dma_map.h b/boards/narinfc/h7/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..428ef3f0f9 --- /dev/null +++ b/boards/narinfc/h7/nuttx-config/include/board_dma_map.h @@ -0,0 +1,49 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + +#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */ +#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */ + +#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0 /* DMA1:83 */ +#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0 /* DMA1:84 */ + + +// DMAMUX2 (BDMA) +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */ diff --git a/boards/narinfc/h7/nuttx-config/nsh/defconfig b/boards/narinfc/h7/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..a0e6f39246 --- /dev/null +++ b/boards/narinfc/h7/nuttx-config/nsh/defconfig @@ -0,0 +1,267 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_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/narinfc/h7/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="PX4 NarinFC-H7" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743XI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004c +CONFIG_CDCACM_PRODUCTSTR="NarinFC-H7" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="VOLOLAND" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXAMPLES_CALIB_UDELAY=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM15=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_SERIAL_CONSOLE=y +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_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_IFLOWCONTROL=y +CONFIG_USART6_OFLOWCONTROL=y +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/narinfc/h7/nuttx-config/scripts/bootloader_script.ld b/boards/narinfc/h7/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..c2eba58f26 --- /dev/null +++ b/boards/narinfc/h7/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,223 @@ +/**************************************************************************** + * 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 STM32H743XIH6 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 +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + DTCM1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + 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(.); + } > AXI_SRAM AT > FLASH + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_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) } + + .ramfunc : { + _sramfuncs = .; + *(.ramfunc .ramfunc.*) + . = ALIGN(4); + _eramfuncs = .; + } > ITCM_RAM AT > FLASH + + _framfuncs = LOADADDR(.ramfunc); +} diff --git a/boards/narinfc/h7/nuttx-config/scripts/script.ld b/boards/narinfc/h7/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..f213ad2ff4 --- /dev/null +++ b/boards/narinfc/h7/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 STM32H743XIH6 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 = 1920K + + 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/narinfc/h7/nuttx-config/test/defconfig b/boards/narinfc/h7/nuttx-config/test/defconfig new file mode 100644 index 0000000000..8b909c1e88 --- /dev/null +++ b/boards/narinfc/h7/nuttx-config/test/defconfig @@ -0,0 +1,270 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_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/narinfc/h7/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="NarinFC-H7" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743XI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004c +CONFIG_CDCACM_PRODUCTSTR="PX4 NarinFC-H7" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="VOLOLAND" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXAMPLES_CALIB_UDELAY=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM15=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_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_TESTING_OSTEST=y +CONFIG_TESTING_OSTEST_FPUTESTDISABLE=y +CONFIG_TESTING_OSTEST_STACKSIZE=10240 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_SERIAL_CONSOLE=y +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_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_IFLOWCONTROL=y +CONFIG_USART6_OFLOWCONTROL=y +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/narinfc/h7/src/CMakeLists.txt b/boards/narinfc/h7/src/CMakeLists.txt new file mode 100644 index 0000000000..a218bdd4f3 --- /dev/null +++ b/boards/narinfc/h7/src/CMakeLists.txt @@ -0,0 +1,67 @@ +############################################################################ +# +# Copyright (c) 2020 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +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 + 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/narinfc/h7/src/board_config.h b/boards/narinfc/h7/src/board_config.h new file mode 100644 index 0000000000..f8a1824ebc --- /dev/null +++ b/boards/narinfc/h7/src/board_config.h @@ -0,0 +1,246 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +#include +#include +#include +#include + +/* LEDs */ +#define GPIO_nLED_RED /* PI5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5) +#define GPIO_nLED_GREEN /* PI6 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN6) +#define GPIO_nLED_BLUE /* PI7 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN7) + +#define BOARD_HAS_LED_PWM 1 + +/* ADC channels */ +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA1 */ GPIO_ADC1_INP17, \ + /* PA2 */ GPIO_ADC12_INP14, \ + /* PF11 */ GPIO_ADC1_INP2, \ + /* PC4 */ GPIO_ADC12_INP4, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PC5 */ GPIO_ADC12_INP8, \ + /* PC1 */ GPIO_ADC123_INP11, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13 + +/* Define Channel numbers must match above GPIO pins */ +#define ADC_BATTERY1_VOLTAGE_CHANNEL 16 /* PA0 */ +#define ADC_BATTERY1_CURRENT_CHANNEL 17 /* PA1 */ +#define ADC_BATTERY2_VOLTAGE_CHANNEL 14 /* PA2 */ +#define ADC_BATTERY2_CURRENT_CHANNEL 2 /* PF11 */ +#define ADC1_6V6_IN_CHANNEL 4 /* PC4 */ // SPARE1_ADC1: ADC6.6 +#define ADC1_3V3_IN_CHANNEL 18 /* PA4 */ // SPARE2_ADC1: ADC3.3 +#define ADC_RSSI_IN_CHANNEL 6 /* PF12 */ +#define ADC_SCALED_V5_CHANNEL 8 /* PC5 */ // VDD_5V_SENS: Motherboard 5V voltage detection +#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL 11 /* PC1 */ // SCALED_V3V3: Sensor power detection +#define ADC_HW_VER_SENSE_CHANNEL 12 /* PC2 */ +#define ADC_HW_REV_SENSE_CHANNEL 13 /* PC3 */ + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY1_CURRENT_CHANNEL) | \ + (1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY2_CURRENT_CHANNEL) | \ + (1 << ADC1_6V6_IN_CHANNEL) | \ + (1 << ADC1_3V3_IN_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \ + (1 << ADC_HW_VER_SENSE_CHANNEL) | \ + (1 << ADC_HW_REV_SENSE_CHANNEL)) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +#define GPIO_HW_REV_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN14) +#define GPIO_HW_REV_SENSE /* PC3 */ GPIO_ADC12_INP13 +#define GPIO_HW_VER_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN3) +#define GPIO_HW_VER_SENSE /* PC2 */ GPIO_ADC123_INP12 + +/* CAN Silence Silent mode control */ +#define GPIO_CAN1_SILENT_S0 /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_CAN2_SILENT_S1 /* PH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN3) + +/* HEATER */ +#define GPIO_HEATER_OUTPUT /* PA8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PWM */ +#define DIRECT_PWM_OUTPUT_CHANNELS 14 +#define BOARD_NUM_IO_TIMERS 4 + +/* Power supply control and monitoring GPIOs */ +#define BOARD_NUMBER_BRICKS 2 + +#define GPIO_nPOWER_IN_ADC /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_CAN /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN0) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_ADC /* Brick 1 is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_CAN /* Brick 2 is Chosen */ +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB is Chosen */ + +#define GPIO_VDD_5V_HIPOWER_EN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11) +#define GPIO_nVDD_5V_PERIPH_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_RC_EN /* PG5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5) +#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7) + +#define GPIO_VDD_5V_HIPOWER_OC /* PJ3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN3) +#define GPIO_nVDD_5V_PERIPH_OC /* PJ4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN4) + +/* Power switch controls ******************************************************/ +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_EN, (on_true)) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) + +#define SPEKTRUM_POWER(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_EN, (on_true)) +#define READ_SPEKTRUM_POWER() px4_arch_gpioread(GPIO_VDD_5V_RC_EN) + +/* Tone alarm output */ +#define TONE_ALARM_TIMER 15 /* timer 15 */ +#define TONE_ALARM_CHANNEL 1 /* PE5 TIM15_CH1 */ + +#define GPIO_TONE_ALARM_IDLE /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5) // ALARM +#define GPIO_TONE_ALARM GPIO_TIM15_CH1OUT_2 + +/* USB + * OTG FS: PA9 OTG_FS_VBUS VBUS sensing + * HS USB EN: PH15 + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) +#define GPIO_HS_USB_EN /* PH15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN15) + +/* High-resolution timer */ +#define HRT_TIMER 3 /* use timer3 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + + +#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2 +#define RC_SERIAL_PORT "/dev/ttyS5" +#define RC_SERIAL_SINGLEWIRE + +/** + * GPIO PPM_IN on PB4 T3C1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART8 PE0 + * Inversion is possible in the UART and can drive GPIO_PPM_IN as an output + */ +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +/* RSSI_IN */ +#define GPIO_RSSI_IN /* PB0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0) + +/* Safety Switch is only on FMU */ +#define FMU_LED_AMBER /* PE12 */ (GPIO_OUTPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN12) // FMU_LED_AMBER +#define GPIO_BTN_SAFETY /* PE10 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN10) // SAFETY_SW + +#define GPIO_LED_SAFETY FMU_LED_AMBER + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) +#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_OC)) + + +/* 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 BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_HW_REV_DRIVE, \ + GPIO_HW_VER_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_CAN2_SILENT_S1, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_CAN, \ + GPIO_nPOWER_IN_ADC, \ + GPIO_nPOWER_IN_C, \ + GPIO_nVDD_5V_PERIPH_EN, \ + GPIO_nVDD_5V_PERIPH_OC, \ + GPIO_VDD_5V_HIPOWER_EN, \ + GPIO_VDD_5V_HIPOWER_OC, \ + GPIO_VDD_5V_RC_EN, \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_OTGFS_VBUS, \ + PX4_GPIO_PIN_OFF(GPIO_HS_USB_EN), \ + GPIO_RSSI_IN, \ + FMU_LED_AMBER, \ + GPIO_BTN_SAFETY, \ + } + +__BEGIN_DECLS +#ifndef __ASSEMBLY__ + +extern void stm32_spiinitialize(void); +extern void board_peripheral_reset(int ms); + +#include +#endif /* __ASSEMBLY__ */ +__END_DECLS diff --git a/boards/narinfc/h7/src/bootloader_main.c b/boards/narinfc/h7/src/bootloader_main.c new file mode 100644 index 0000000000..3a0e1a1904 --- /dev/null +++ b/boards/narinfc/h7/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2020-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @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_configgpio(GPIO_OTGFS_VBUS); +} + +__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/narinfc/h7/src/hw_config.h b/boards/narinfc/h7/src/hw_config.h new file mode 100644 index 0000000000..05cb9e67e3 --- /dev/null +++ b/boards/narinfc/h7/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/**************************************************************************** + * 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/ttyS4,57600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1183 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#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/narinfc/h7/src/i2c.cpp b/boards/narinfc/h7/src/i2c.cpp new file mode 100644 index 0000000000..124fc2375c --- /dev/null +++ b/boards/narinfc/h7/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusInternal(3), + initI2CBusExternal(4), +}; diff --git a/boards/narinfc/h7/src/init.c b/boards/narinfc/h7/src/init.c new file mode 100644 index 0000000000..a8f3bf4ad3 --- /dev/null +++ b/boards/narinfc/h7/src/init.c @@ -0,0 +1,224 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + + bool last = READ_SPEKTRUM_POWER(); + /* Keep Spektum on to discharge rail*/ + SPEKTRUM_POWER(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + SPEKTRUM_POWER(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_PERIPH_EN(true); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + board_control_spi_sensors_power_configgpio(); +} + +/**************************************************************************** + * 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) +{ + /* Power on Interfaces */ + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + board_control_spi_sensors_power(true, 0xffff); + SPEKTRUM_POWER(true); + + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure SPI interfaces (after we determined the HW version) */ + stm32_spiinitialize(); + + /* 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_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + +#ifdef CONFIG_MMCSD + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0); + } + + if (mmcsd_slotinitialize(0, sdio_dev) != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n"); + } + + /* Assume that the SD card is inserted. What choice do we have? */ + sdio_mediachange(sdio_dev, true); +#endif /* CONFIG_MMCSD */ + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + return OK; +} diff --git a/boards/narinfc/h7/src/led.c b/boards/narinfc/h7/src/led.c new file mode 100644 index 0000000000..79792ca1a2 --- /dev/null +++ b/boards/narinfc/h7/src/led.c @@ -0,0 +1,111 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file 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[] = { + FMU_LED_AMBER, // Indexed by LED_SAFETY (defaulted to an output) +}; + +__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/narinfc/h7/src/spi.cpp b/boards/narinfc/h7/src/spi.cpp new file mode 100644 index 0000000000..5198ffb11e --- /dev/null +++ b/boards/narinfc/h7/src/spi.cpp @@ -0,0 +1,66 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortE, GPIO::Pin4}), + initSPIDevice(DRV_IMU_DEVTYPE_ADIS16470, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortE, GPIO::Pin7}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortG, GPIO::Pin6}, SPI::DRDY{GPIO::PortJ, GPIO::Pin0}), + }, {GPIO::PortE, GPIO::Pin3}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortF, GPIO::Pin5}), + initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortE, GPIO::Pin4}), + }), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin3}, SPI::DRDY{GPIO::PortB, GPIO::Pin15}), + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin14}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortB, GPIO::Pin15}), + initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortG, GPIO::Pin10}), + }), + initSPIBusExternal(SPI::Bus::SPI5, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin4}), + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}), + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin13}), + }), + initSPIBus(SPI::Bus::SPI6, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin12}, SPI::DRDY{GPIO::PortH, GPIO::Pin5}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortE, GPIO::Pin15}, SPI::DRDY{GPIO::PortH, GPIO::Pin5}), + initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortI, GPIO::Pin8}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/narinfc/h7/src/timer_config.cpp b/boards/narinfc/h7/src/timer_config.cpp new file mode 100644 index 0000000000..0885466267 --- /dev/null +++ b/boards/narinfc/h7/src/timer_config.cpp @@ -0,0 +1,84 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, 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}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); + +constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = { + initIOTimer(Timer::Timer8), +}; + +#define CCER_C1_NUM_BITS 4 +#define POLARITY(c) (GTIM_CCER_CC1P << (((c)-1) * CCER_C1_NUM_BITS)) +#define DRIVE_TYPE(p) ((p)|GPIO_OPENDRAIN|GPIO_PULLUP) + +static inline constexpr timer_io_channels_t initIOTimerChannelLED(const io_timers_t io_timers_conf[MAX_LED_TIMERS], + Timer::TimerChannel timer, GPIO::GPIOPin pin, int ui_polarity) +{ + timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, timer, pin); + ret.gpio_out = DRIVE_TYPE(ret.gpio_out); + ret.masks = POLARITY(ui_polarity); + return ret; +} + +constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { + initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}, 1), + initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}, 2), + initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel3}, {GPIO::PortI, GPIO::Pin7}, 3), +}; diff --git a/boards/narinfc/h7/src/usb.c b/boards/narinfc/h7/src/usb.c new file mode 100644 index 0000000000..3d86aca280 --- /dev/null +++ b/boards/narinfc/h7/src/usb.c @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/boards/narinfc/h7/test.px4board b/boards/narinfc/h7/test.px4board new file mode 100644 index 0000000000..a9fb25cc6a --- /dev/null +++ b/boards/narinfc/h7/test.px4board @@ -0,0 +1,11 @@ +# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set +CONFIG_DRIVERS_ADC_ADS1115=n +CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n +CONFIG_DRIVERS_IRLOCK=n +CONFIG_DRIVERS_PCA9685_PWM_OUT=n +CONFIG_DRIVERS_UAVCAN=n +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n +CONFIG_BOARD_TESTING=y +CONFIG_DRIVERS_TEST_PPM=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_MICROBENCH=y