From 3ddeb2e70e15882ab33be486057e722bfbcc86a0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 8 Mar 2022 14:05:56 -0800 Subject: [PATCH] Add nxp_fmurt1062-v2 FMUM px4io_update: Add px4io FW on nxp_fmurt1062-v2 nxp_fmurt1062-v2:Use DMA on SPI nxp_fmurt1062-v2:Timer configuration for 1 channel per group (timer) nxp_fmurt1062-v2:Normalize with V5X - start PX4IO and Mavlink on TELEM2 nxp_fmurt1062-v2:Update PX4IO Firmware nxp_fmurt1062-v2:Normalize boardconfig to upstream nxp_fmurt1062-v2:Corect roataion of ICM20602 nxp_fmurt1062-v2 RC04 HW Changes nxp_fmurt1062-v2:Use TJA1103 PHY nxp_fmurt1062-v2:Update to NuttX 10.3+ nxp_fmurt1062:Use Buffer based HW flow control nxp_fmurt1062-v2:Free Memory nxp_fmurt1062-v2:Remove fixed wing --- .ci/Jenkinsfile-compile | 1 + Makefile | 1 + ROMFS/px4fmu_common/init.d/rcS | 2 +- boards/nxp/fmurt1062-v2/default.px4board | 82 +++ .../fmurt1062-v2/extras/px4_io-v2_default.bin | Bin 0 -> 39924 bytes boards/nxp/fmurt1062-v2/firmware.prototype | 13 + .../nxp/fmurt1062-v2/init/rc.board_defaults | 21 + boards/nxp/fmurt1062-v2/init/rc.board_mavlink | 7 + boards/nxp/fmurt1062-v2/init/rc.board_sensors | 90 +++ boards/nxp/fmurt1062-v2/nuttx-config/Kconfig | 41 ++ .../fmurt1062-v2/nuttx-config/include/board.h | 430 +++++++++++++++ .../fmurt1062-v2/nuttx-config/nsh/defconfig | 276 ++++++++++ .../nuttx-config/scripts/ocram-script.ld | 299 ++++++++++ .../nuttx-config/scripts/script.ld | 163 ++++++ boards/nxp/fmurt1062-v2/src/CMakeLists.txt | 58 ++ boards/nxp/fmurt1062-v2/src/autoleds.c | 191 +++++++ boards/nxp/fmurt1062-v2/src/automount.c | 304 +++++++++++ boards/nxp/fmurt1062-v2/src/board_config.h | 508 +++++++++++++++++ boards/nxp/fmurt1062-v2/src/can.c | 153 ++++++ boards/nxp/fmurt1062-v2/src/i2c.cpp | 41 ++ .../fmurt1062-v2/src/imxrt_flexspi_nor_boot.c | 64 +++ .../fmurt1062-v2/src/imxrt_flexspi_nor_boot.h | 175 ++++++ .../src/imxrt_flexspi_nor_flash.c | 198 +++++++ .../src/imxrt_flexspi_nor_flash.h | 349 ++++++++++++ boards/nxp/fmurt1062-v2/src/init.c | 336 ++++++++++++ boards/nxp/fmurt1062-v2/src/led.c | 115 ++++ boards/nxp/fmurt1062-v2/src/manifest.c | 157 ++++++ boards/nxp/fmurt1062-v2/src/mtd.cpp | 133 +++++ boards/nxp/fmurt1062-v2/src/sdhc.c | 128 +++++ boards/nxp/fmurt1062-v2/src/spi.cpp | 388 +++++++++++++ boards/nxp/fmurt1062-v2/src/timer_config.cpp | 154 ++++++ boards/nxp/fmurt1062-v2/src/usb.c | 129 +++++ foo.txt | 1 + .../nxp/imxrt/include/px4_arch/px4io_serial.h | 169 ++++++ .../nuttx/src/px4/nxp/rt106x/CMakeLists.txt | 2 + .../rt106x/include/px4_arch/px4io_serial.h | 36 ++ .../nxp/rt106x/px4io_serial/CMakeLists.txt | 36 ++ .../nxp/rt106x/px4io_serial/px4io_serial.cpp | 516 ++++++++++++++++++ 38 files changed, 5766 insertions(+), 1 deletion(-) create mode 100644 boards/nxp/fmurt1062-v2/default.px4board create mode 100755 boards/nxp/fmurt1062-v2/extras/px4_io-v2_default.bin create mode 100644 boards/nxp/fmurt1062-v2/firmware.prototype create mode 100644 boards/nxp/fmurt1062-v2/init/rc.board_defaults create mode 100644 boards/nxp/fmurt1062-v2/init/rc.board_mavlink create mode 100644 boards/nxp/fmurt1062-v2/init/rc.board_sensors create mode 100644 boards/nxp/fmurt1062-v2/nuttx-config/Kconfig create mode 100644 boards/nxp/fmurt1062-v2/nuttx-config/include/board.h create mode 100644 boards/nxp/fmurt1062-v2/nuttx-config/nsh/defconfig create mode 100644 boards/nxp/fmurt1062-v2/nuttx-config/scripts/ocram-script.ld create mode 100644 boards/nxp/fmurt1062-v2/nuttx-config/scripts/script.ld create mode 100644 boards/nxp/fmurt1062-v2/src/CMakeLists.txt create mode 100644 boards/nxp/fmurt1062-v2/src/autoleds.c create mode 100644 boards/nxp/fmurt1062-v2/src/automount.c create mode 100644 boards/nxp/fmurt1062-v2/src/board_config.h create mode 100644 boards/nxp/fmurt1062-v2/src/can.c create mode 100644 boards/nxp/fmurt1062-v2/src/i2c.cpp create mode 100644 boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.c create mode 100644 boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.h create mode 100644 boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.c create mode 100644 boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.h create mode 100644 boards/nxp/fmurt1062-v2/src/init.c create mode 100644 boards/nxp/fmurt1062-v2/src/led.c create mode 100644 boards/nxp/fmurt1062-v2/src/manifest.c create mode 100644 boards/nxp/fmurt1062-v2/src/mtd.cpp create mode 100644 boards/nxp/fmurt1062-v2/src/sdhc.c create mode 100644 boards/nxp/fmurt1062-v2/src/spi.cpp create mode 100644 boards/nxp/fmurt1062-v2/src/timer_config.cpp create mode 100644 boards/nxp/fmurt1062-v2/src/usb.c create mode 100644 foo.txt create mode 100644 platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/px4io_serial.h create mode 100644 platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/px4io_serial.h create mode 100644 platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/px4io_serial.cpp diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index f6a6275632..aafeb12539 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -85,6 +85,7 @@ pipeline { "nxp_fmuk66-v3_default", "nxp_fmuk66-v3_socketcan", "nxp_fmurt1062-v1_default", + "nxp_fmurt1062-v2_default", "nxp_ucans32k146_canbootloader", "nxp_ucans32k146_default", "omnibus_f4sd_default", diff --git a/Makefile b/Makefile index 53b90e3d01..f866e6c420 100644 --- a/Makefile +++ b/Makefile @@ -319,6 +319,7 @@ px4io_update: cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v5x/extras/px4_io-v2_default.bin cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6x/extras/px4_io-v2_default.bin cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6c/extras/px4_io-v2_default.bin + cp build/px4_io-v2_default/px4_io-v2_default.bin boards/nxp/fmurt1062-v2/extras/px4_io-v2_default.bin # cubepilot_io-v2_default cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 04a07cfee9..da77e96639 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -162,7 +162,7 @@ else param select-backup $PARAM_BACKUP_FILE fi - if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X + if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X NXP_FMURT1062_V2 then netman update -i eth0 fi diff --git a/boards/nxp/fmurt1062-v2/default.px4board b/boards/nxp/fmurt1062-v2/default.px4board new file mode 100644 index 0000000000..963b6649b1 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/default.px4board @@ -0,0 +1,82 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_LINKER_PREFIX="ocram" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS6" +CONFIG_BOARD_SERIAL_GPS3="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_COMMON_LIGHT=y +CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y +CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y +CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=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_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=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_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/nxp/fmurt1062-v2/extras/px4_io-v2_default.bin b/boards/nxp/fmurt1062-v2/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000000000000000000000000000000000..51403914013d2f9cecc849dfda750db977a95303 GIT binary patch literal 39924 zcmeFZ{d*Ht+BklnnMpEj15ICmzELJgfwbi%P;jfj8j|+(CB-UrpH)G3u;>oL+A8XU z`yzqj8ZADH*7d1W5v{w6;;tkRm!dUQbk~=4Hv!oPs4P`n$F{nj(7;TZCiA^cQiT0H z*Y&+Vf57L5X3osH&pG$G&pG$|sbeY#OLKrfQT+e@{%>i(2Y@V00GX=-sf_{owF>4e zx3RIynR%Q(jSZbn{y30t<9f1h0+DqSE|n|(R$i@gSuT~!`c{VEE(Qc{3J3rotbZB! z#~Bcm0F*6oFTAcqTr1{V7t}9kSlC!4a-vbpljg5-5ya++^W3wf6^@zWG-)>3asTY7 zXX!Lrj(TQK6K6`Zqd%WEQ!HCGPt2FfqMovvsAoyOXl_DJEy3tHm_O%JwA=41k}QNU zMPiX;iHfV!&!O8>Pr@=zf>L!1F*01mczBxCDzcI*y2IrnD_B;{l3dXNYnI3!ApO&% z-?Jw^LC>KT=+}RhjV8vCZ(VjN&%97fOxXJQ<@iE%ilu+U84UgRzk+v_06 z0dlYz^M{Emk8l|SV@&>y;Yv4nTIrzZz#@dS+kSAHmayC!YlM2O`54Ory)cv&4{@cNeB0Tv2Fo5n~F1@26{Jsz#1{I!-lmm;zkeUUjYM za|uO5n=R4My?L&4BGZNlLMfz~J0+abfogm@bh&hWXSo|c@pkHnm|C)HNS+F*@3T6iCw zW!Adfwif!nxn-THpDE{quBfN=tlY7wsO@^`pn99&7-5{5B3K6ez3Od3dz~rZ*>rhc z2h_Fpt9>paAWeDXJDjc2UH6y?LQ%P6Q*m2?G%)5cwbylQ>QHy2p2cl9i}XERH(+Y7 zs}68D)$hY;deMGw_PK}$J?ht#TQmV9vR(bg|L|Cjx4Pd-JSc<9Flx#wEh?J=J2riy zdH~4Z#y?TL_JN219ZqBD6LqIBt1`5fjUXm72-bI1ukfzwwVV1un2@UjEbftf7q)G^ zb%P1Ny6O8N--Yh2`jF#1%6rCH6lx;{P~C5Bd&h9=hSs)>6RzlhLsMoaYYDHjw%xi8 zgl}bQbim<=dK{Wkn4C>`-FX=*t`0q=uCwp=p~~i{=U!v5ISQM>n&)~-Z55y*Kj^T4 zCC}v|cD6%YcQ=qP^N9xDF^p|WpW_Wb_Ae0@bD&m zLk0e|Dgh#Qj&r!6kCuT5aRFENPn!XJbs!%%M?Lpj+VZ3x|1TN=f-ax+#xq3GB{h)@dXax#Ei#@3l`RRjNMMz(SfOO>(h3z6 z6$FuB>VHz*VK)WxvCC(|nlhpZJ|TrOkhg=TelS-Dba=-m0q;;nlcuao?%$N(Slrg- zED13e+MV?I;)VO1T~1xNISPxW)`JDeUt^ZGW z*WVoVn7R64xjE`t$=3fc?P4|5(Kx>FFW+#(>FYHM>? z%sAivp6Yb~sfe9WJ%Fqgm}vl#858hH8G?_@0NxbHXaci_iT$x5=>E|J;N1=*I}4wqz&ZryApEPIRCUYFO{9sp}TzF~{k zsSlwlLnRY2F-o|ZXjP@?g?q_5n6V?`jDhXdpnyT3^Pw>G>#9C`pjLWSDkF${RjiTB>sCsQ>zvYY zaizreJeHcTC8{~sa2C?etTE=fIz@Z`z%Y}$Qu0a;f*6n9@Cj5F1dUccm}#Z;?RE5h zs`a9*DR%^2(n*O*kjv}DO4bpCGF^;#&QEm|Q$K(`km1g#FOT28Q;214GY#14B=J14G}A={%)`%Vt8~j%93n9N&eR zh`@Y1meVnRc%pd&-h|7Df%!ECGNhWZ*O?K5$UNlxiew|nJWR3=d^ORGhJ0U5G}B&; z!EIx_ciUKom*Uo52as(u1x#m5)ipWn=nj^Rh%WZRI#-s6tUzX^bQ_aMsXE2Y*|J17 z+#K~(<%t($osFUVsY;dgsglP!CTH8&Fz2Rizmc1XW3SqR5b`_*^FZ_JJ(%-a~raRnIez} zvd zf$;cD;P0Oad|tp~-GI?69M+VrT6N!mt4O4$A};{n!TjX^fXSSM zq4eYF+IOU7{3B*m4`hMrcn)#lpH1F=&3d_P*sVK06H?{}UI!t7?^ z$!sPltGBb*zn`7}p|#U;SFwM-pHW%Q9Uc8&slV!rK(;0H?O4tukB#Mc(~t$>)=fK9 zbO4zL?-Fo#9T&+3Am@{oor()Y4cGI^9NCI3>fJ3vwIDgiqx8!%B09 zq{qkAe9sijN6IqlF?tfnu_RYoItXQ#utGi0I*X2fJC^gX$FhAa$9qz(5mw)o>2u&+ zb!q*NesN%AesaUEx_S&Gk`yp|p#LlKtHY{IIIPYwnfw|4ZBBFOq&m-p7V~Ql$0|&@ z{wL_{E&EiPa8l)j-009&T`1FL2 zehDgSLQAB4;^182OH`qFnDLVvC}wn2I(mkmj-&a@!dK!=%M{=L4atNky>`f6l{vsi z@&QO=GDSgK@ZwKjYa=Z8piJM>JvcC(^H1b9ay>_XGr7Cu`NL#ohji-(UBtvYFp!EQ zS6Vo@U<w~vHxXh8~YQ4wp8M%Fj!Q@qOqa7?4DaiQy`g&Zo4#;4lwewJ{ zR4DeNs@-&rtuJ=w`gc2R;d;zP$})fqCFnl+bK>)z*2i=G#s1ySf?(By^|&O+62#7Q z0r^{ErjMQ;P1&tcYWz7-jr+e+J5Uu@84QE9jbt0D)p9Q|oKkmHF{D%b~$4?6Y7C@)x(;sqo$ zEVq%(x?$PDfk5%=kUTgWPsg`zK;-`97T;wFY#7z^hik3jv{tkv#X-m;Ku%6mmi2*JB{b39gh3o>al!fIEnTr~8DScprX$%u_)5MPYaeUN*E}nxUfNlLq$0lyY6T z$e{a#S}OYze~~lGW8pkfmd%EynCZ7YiA*z*uY}JG7a1}?abjBge1a=A4Q52Nt3z^T zc{J4$g)`0H%1)ea|6d8N^x|n>Ejsqw(G2dc&i#|LU+{>Xdx6MTd>J z()W=>{Yf8*I%}s$btx`V0GdK3(&aMHl#$7@2{h%439xXHTtg17#+q^_^_H*C!FH@E zf1iY#4w@300CP2Fh<+T*cFYiF+=^2xwX!)ncrR)Iva=6@*YBZvDu?wUXK$MN+XI)*OY5fM4c&F7NMW{vZ1XtI z8>;p=&7s#XIJX*3zkcDdtv?Jo&QHtR;_%nH_uT`oPd!>!yIcZefoU)tSWlC`{=h}f}PSE{8`LJ#RrFI4o zNR`R}NIcF(rUNpk*DCr3T?rjtyMc?C^mYv7>9}tQ~VQE zQO?-gp^G5h$>8rgK9<$~`NLx?-`ja0RxznXq%{bbGi&^pY6{~G-F1$>!x6}4LKMR% zk_?r^+vYx=n!|=`{pjWHy4Rdvh0g8#{H|hu=*CL_xgB)3prz@)&{Zd8I*I{L#k=rK z45U)!N^=KS;%bau0rFFoE6o^$GSqYW(WArM9Tt+E^3$H)2E?vXn~aWU3K*J@MZnbF z%ZfK&)Hb(zz}o9cuT<0FB^(IV0U*{yW|IydiZS*MCl>~x*NdupJ=Oixv+>7qu)P>W z);m1Co(nPrX&XcRff#2;mCPBmti#h@M|*a8z}n#f5;&5EF$Gx6;R2keqRNUsC@!%h z5}PRKGxaa57zf9e$@;7 zat;KrQn{WdPRGm^?*XW&4ShU}ShVlsVYceyVO`bZYKa|4lM1$_r_T(tH=^gOF_5cN zc8dpBf^KVQ@)e9p*61{#@=&z3&yNjrNQN zwsWDS-@!ncT|Dz0gd(>Q6L*518t(5hiwn0D;3ABw7Wo#It6>vnx1hxfE5}3ab!vc> zbhv2C!U{e#x6#&+Z%5=6ZQ};0Tp6kqXS;1uiNtPMSh*q$bH0b0`YgDOAojgs;NBZ% z9;jGXfYp93G6T7&e*L#R6)k)-0@>N&Oy9za8DUL%TVuDp;XC&zOR`zEGCwp2_exNf zHDvKEtYAV<)#{FaehSKHpB8*vZk6WZ68w?O;E!bngY`qXjbyQZq4QurkSWbK?Mc%e z5z@yr=1Hh3FXdmR@)KF1tm(RrKvjEFbCY|y_;Zm)Dco-Ns`S&0>9f&2V6ml242i~A z>;4C@yRPxQVXjJV-QQ8`z8c%`(P1cib=!ODfE|&aCRe&8JX2(>=;f+*L|%%W83u&N z>v7JyyvZtBB~*F+89^EVMBa&mrTL=v^BMRmcY!EKh0-o(?WYzA%BG0LQhEKep7O0g zK8w$-N93mQ0`u&8L`vfOr5=eDE%iXYi6hH?spuY?yTrpmG25Nx zL*&+2nLEoz?K^Agdy9sMb)2*2)>pLyA#sMh6$8?(>a6trDiz3H6_KCECS{FQ^u5XyWTH`W@<02aLW4PLWCu%9pAA7ndQpY98=S6h9juFrLh4 zT&>#eYkbV;0JB=^uG71VB)z+co=%I-eNisLv<-!)bECM^_E*}qRc2JLDetI#DOs;` zmq_z`h#ZNT`p$Kts&gIGrcJdC`+zjW z_xkpCvV>)sN<-)ssYBZBWJ7Jl2!i!6|4K(2!gnr?jx@;U%J97 z^D*9BKU6SYCZa8-7PamS2*UbH9(u3}>vd)UTX!JxxOyli0N6;#;rv%h;*O^Jq*9m4 zjIhSe91l^wM^ir1xKjOTP1&lhcXBBUJngM#u_;i0Fr~GotirmB+C3D5$DF!J&9#j@ z2Bv<-i&EI6vCH^0qtPVUeaxoaPCg7)c0HwaTGItVmO)B;&Oevw{=784?zE;{dujY7 z0;U=l-CLScpk3ZwmEIyQ)jEUy~bTvnRy7?v-+9hEiUr(?pn;wD=XEw|q)>d-(UBQc|<5?Jy<1rmR z=`;51RZBcfS5}W1qpr-J#TdGlVIZX{rI-yP^1GOTxfGAL;Xusj0P;|bTHjgRd3jbq z|13QD@i1Bf)=XT8HRUfFcfdsDd!2r(7cas(`~;qbP&K;DdTr8R>#3?y%yE7cQL zUp@GrzSWrWFhnY2Tj&8sRWT=c)VjdBvE=Q*`nu&!f!o>Mtf>$=`fhOms49A)!dy&YVnhA}^|?g3Vy zzNzyu0srO!AivZ!<$OZGmIg!~h;!E72Q)=Z*szYy@>g^RBl~aVYoz9j+C!`18WAir zFhn>bFKu^b58jMH$Zftx;ukTa$L>8adV6-(;7xS>)%R7ne!E<&E^eQvE*?UQzm%_$ z7R9)~+@SKy(KW^qhN)E-+jXPw7#GF3dB{%ZaayLlm(rB-Udn^*ZtAOn^8DaqcsKUo z>+v*<$dgH2vhv2-KCwUN~ zCH%EbHQb8t)x1$#5(c3`<&5vE17g}=L-{(I@dLFCz;-Nzh?qR7F0muKzGjbe`Z2WR zO(zMr5k1JVTjiR6pmMW#jGjQGDY+e^X9S!XL77QqMe@d)zsYUn7C26KJA`BihEu%v zvXu+uz<1F}QveB$^C*9cyI4A|4hXAN!PL;Vc0AgL6s4v z5y;QS)k%JDEwNsNc z?jpP@R`(x>8HElBgdz{J+;R_%r0$S(c!{s|K~%||Ld#n30qcG-t>Hct<02)1h&4%P z^J$Fs`nvWnnZ^b=?2)MEnv-PBS@jGNR9$IS7?~0IpQH^lW<-vsJVezFAn*n{gUA%E zjZBB?ej10N^GdgmOvZnJd~*Z!ez>N(2c;kFw1dwf1gLx~JZac|N*6Q&Sd}sL?W$;^UY4w)Z&?5_2LshI)EQ8gtJ7qHrImhReQ89~gqvPJqPrFDNjx&OWw znBk_q|1G|06XlU-$G>oK4)j!6pQap-Q-7$vAMFEjtLiG@uqlKv+K0&BVrERCb5#!8 zeP|{vdsRB)xhnO|{WGj7hvG;$J1O%!u8{a3tle;*&+_17PJNh-n6F zq=<|NilwDLjU}4`?9bLvon|usA+rIIgX*Qo8&j#LUWmy$u7Sv?ax9#-)oR}Q!~nuy z4AfrJVN^yjMx-Mq^r0ofyi^2j2_1p%Sco*~Xzda8`aUjlW2$^et?p|k+TwSIbA;-C zAh!57GL455Io-mTf_g!<_2n<2r{Gz&ppU{;kDr${rB{old__}m#ug68d^L7NYGcS| zz;{xNCw&vW4_)-@D|5r;TewI)AhIMT`YI&>pSxqDWW5utz3YK&Nu>15IlmsF&zGd~ zEtmIY>xMjE!Gm5WA3m1yqg44Sq+7(hq}}3|axx_?A0eWj%#8T+75^WlAU_!g+qI$1l1ubU+r=@dN6&qNtmRue9eJ(}u~IrJZj{({mnp$T znh=mbP5NVCj;1^{{_R+fH+_<)HPF4ad7}3reI+0MKPe})3hBaPNy9Kz^)!qShP;NbV7x?vC{o zel^}K*?*>w7*TiKw_`bv(O!Eyug2CWZ0_x7-DJnNIyy$O*qM%pN3wKxtOwGn{b>BL zaT+VpltoGE`}sQdx(qOXSaD@zs%u;oa!Muc-Oj~VSSV-J^}8f|N(B!hQ`HI#W~vR& zikTu=*&M#;*N0PksBAL6(eW!EdYPWt9UAreqVC>Np4sKx85}4A;cDy+I% z6u0Dvm@der}WKAMUX$6pb}wqvbWO} zh1TAVv@a5fPQ4_fN)DIVffO7`^Lrq#B*ALI$XtLCsYqBbSoLNaZ7WOA?|L&MAX1v3 z7SH9~-|>*HQXfW}vb@yel;xp%d72kf>2+Dh-~N!UA|tHZRFTr@D?DI9JDBxAK8mOL zNOeDe8h|pJyZpMN!%$;$ivoSlb^mD?YG`SWoBjf^Oz3dE4jz|tY1CofxAYd6fB zwEIvu<>uxGDL?-#StgyAw?Cw>$P7EqYnHw0TH!v6N4-q|3v(xs6>qfH(LHySo5n_; zz$KJ}Po74DL|6Ait=fTh{b<~)9Ppuin$nb@x{apriTOSTuU5HhE5#ORqo{vSQ%Vvv z%41JQ*E*`C-u2YaUljuLDV4LA)}K;gXrSP%`tyO6qv!7VIzAPFwWtx1wHg;G;}N#v z8I4p^q%uZt2I7s;x0njnr_{Bk-u1J}b5GK<@>J66drDm^!u&slZdBJ^TPe0m8^r-x zpE~D?=M?lfdGVy^FCx{ z?>F^dT0c{O{l&k_HXyZ=ZA|~avhD9jF7-jZdqzARcc*y6;?QFUp?u*LF(a2my)*08 zSq*oKQ>FJ*qX#W1?W1Skl$bYU$BQvopODrRpc6ULqP|{d{--%od0&3R7e!yoCY*_h z?3LJ>bg3LqZ3Mz4OheS;kvsH+^t7{g6tORjvfK-!9C||hCTzpH25N`CDo#dlX|Cut z2!3jyc_-OT7U>pWmxPuWdBS9scY44|asS{SI*tc8SCS}&_7F`k+ z2c+)0Q90cQmA#jx7V){Hb3PDE?qX@s*Xzsd*We<+=w zkIR2^P=_u-3Pg= z4A_eoNQm4PUx_*D_a^;us<{^X5ZM{$TwnN`d|6HU$bDdz7Wt_DRw>rIWGg~oA`j0 z@|nrJ4nzjxf^?r9NKK5+5iHamDiS$&mM@_^n@CeteUswoE224v2VzDO)#ldgZs^N( z7f8*~J)8Gl*wg;*@Kk7RrI}}IEnud*tWG<(@%D{*HLX9krZR2cRS(;niD&b>>YMg9 zqG#V#pS2Tf?~kkdA+_#|yFh|!nrYZxN5^XqWUZPfA@bRHy)WZBE^;3%lFEIWvO%L1 ztrFY&DLvaAl%6Ap)AXe6Qu1!2;Op%iE6Ud?t`v7-O}+pJ2&P1*yMJv_gLK`#lLgC z=}k?U6AY<`g_U=1zjJ%rJ9mcEHwEU$hQzzP0scBzd$HtFma;d%XGap^|si%%^tiT1BW;FgX$>Ps9R@8jndi%!J#kaQ>;Oc&` z#$|x^fF2uD)V+7yp7LA$JB|OC{NFULzJkW>fsTz-YUN|A4{b$+MVjK$=GBxD1Glc& zhW|7?^#}K~0%6sZmko}V&}_RKe0+^SSQsdxzg%NMO^1^Sx7SJdg6vYcN=5$mt>6Cx z;bwvW&bHTOVp?WWWq?e~2M}iKf!w5Ciou-T1N;{T5EwVY1rm^>haq_7dqLl&ciI<) zxUcWZ`oYP1H82HFr!f}tL-mzHT_l@bm(HOh*-WSi)x0~5^0?WBxH$@SW|dp>TZym! zPfxeUG;5V-NVKTj+8*!cQrn2j)i%=N5^#$L$c-sYOmzTRbr?mmS(;hY9(XbG5?6p< zvKVW?JQIIW#717y1MwwT43QEBB74y->t2i)!MOM_=S{b>5hHssOiz8jCslM5myrlLkyvvGsfSLn_030|*Lck)K@-C?wt z^*t+A_ZQ(c5|IyFfM&xnHUk7y2`Ag@kbMmwle2{Oy0jPeL7%3)rb*PcoV2D-sC$J$ zzeRjc-Rnr@>GdyBndRnLN5`hJWh%3LiOMbiu)rT<0Bq9--@oP9FuKZAvsujYJuU4K zbG@`aucpUergF=jUYg-(AzPU|7lU0M+S5lx2UBhH29FOT(@HVJ*DZO)B`Rku^rD(a z{e_K zQkL&UX}4(cwiIVonojNW_xRTpwzgPm>OI00n6a)F5ACx`YxQzVF6}BxANqBUR_1%f zEZ~Y+Kz=*$5VR3BX36_bJ0j9 zn>m6E7s956+{ym0NL>!rlVNJO=WsePpeqOqy z#(}w!Oiohcd)lORNUjQ_P9oj zu*EY+<(Aib2gasCy{E-n?PW)dES;?b|51fqnsOw0HGVn5W#}S#3_W{K)H0{29-5~* z=*~|H_*oe|nnvZKrj%)yx%KdLK5hL2^ zG#-E2|4hM4#m}z3&Qt2?x#iMoZ1jxEcmiU_E!o-k(69sh^d4@6eRrBorB}^rli?A1~I6?R9RcKpdB|Bvxem>P22` zuVXQfb8xPd>uZ#DJ5g9uz6=&gj7V?PWJwI}^m%+8PCi^DWr`FcBMerz*j`uZqgq&( zb36oDyHB%6Rq@-!Q2oC>FcpKjMq(s``=2w;#hF@tJy?YTU1RMiLWulXwTmff@!{@emuv=8)BIs? z{S0i8ba*PhrSGh|#B)|%vg@q6WbavZ$$|H4^xn(W2=Z~+c zCC9q!{v|{3D+35?Uk0B3(VSWOwE4_F)(b+hpX!~H*`;`qufCMAEeW=fA42-utn%lB z^nMeHuu_(5caRl9_}?|1|5n3d5a{~MDt|5r()$h|XtKAdhu8r7%4(G>rrDG_m7$TO zQT9N49SP*)DY)~10W^%~JY#@2tk3?o? z8$u|8ve42Suz;;ncim@0PpD`wiZEHU_IwEDW?H_F`*2_6+U)C29*I^~u7hXKQYdi5tGh#PwG-5Ko3-=tyLK_Po%Mh&_8G+(1x9 zv5NN7@&6vqBxl*)NG-!u+<)pwq&52{mCJf4)Kcjn`#lHTV9O6~$Gb7@Ge3AWZYJ6y znrmhlH{d&m8VHloK)8(mksAn~@rm3(Oc`Oh?*eT7ek+YG&Y%K^jL}5c%J`$0#vnW(s`b&8f9!!tr+2ECrMB1~N zV0l#dZu}0}Fqe-QcpEYBXVp(%;3GU=NcimHun%Vqp}CK%Mwk*YW=3U!Mt7y|I+~%^ zT&o=aqw}|;2KK375eCcA2(aEDSf|yL)?|(vGCr&|gjdvj55qzSF>hO1b2HAAY3m{t z6?fOcf`5h3_rI2pMAm0#L}4=%IuhBC{U70FeH3plR2YReV-Wlfe|gl?0yZl#v2W3P zYAro}hx4?KIdT1nAtNi4X@RaO5o1O}+Q-ndcQhm8N8^viPU}8aVb?t;tORBD)y^7! zZ2a!iHRnyJ&|xYc_p@Ou$;qT&i-;+EV@SW>U6ZFyS#GbqHCz!LXsjTn$yz>pbGV40 zY<xTXvTaSOhUrzMwk;qNiJ$`HGl}H;C_GgsOIhj#W zcJl033@OjETCG-{)jBQHQck9`J^s9?XDbu>;Rs~>CX}AZGqQ`A*wcD+!WH$nOqOrt zLSo8BAy;(3)g0yS{ii&8aut}RKlzfkoRJ&xZoFG=#NBdH)YFW@XfX^ii;wxAmsg(G zvqd9p_U=$rhM>F$__KR}Pp=|+vbzrLMoU`?2mJ?~(ZM3@cfJ~gIj!6v_UZ3NGuXb`_k&=aSwsCobHdOwvnES!#%JZCDEuftc$0aH*(xzhY3AD( z-(hezR79BU{9vV7Fc(EVKPm{$H(MpNbX2}HPG&^A=3|-eEd74Eg6wDpL-$LrYAorl zd;hz=hps*Gr41WWQBw%g7!Z$hqi|125ScAexc5-}`~@aH&6QC(2hYR0PwiEHC#Y!I z`BUxv8NTmTDe@1iF37aq0UykvT}_WsI8dklsXG~*cvuU<7G=xsqg zo-chZ>+!#2%DY(1)O0x^++N43s5mCGxCrNLK~+#b9yS%V*D=@>KsAp!^Dqh*6q))< zwxGo@?_yX@M9(aHAh_EjO_>KN6`2bIna`&7SW{XGGfPhp8y1`m5u3P)1AmdGy}a zr(udkRs?0X)HV~~$fxx{`Cya9W%SAg*DEB69SnY2knYwYgjqo}p6~ChP29V5gSfIm82RpXBK6*5J(P>z? za4?~`l3Z!_;QlSmBQpQT(WBYMK^x{H2x-bllEyP_IHA;Cx(y%^Q;TX7T2uiH#DMg~ zpl3!=4vgweK-Q=nrqK3e{zw^D9bAsjQ5?7-nFMHd29OV8I-F24lVHmqgn3g2_owEW zaeAZlxv5390G$t=ORrSbM|;Xjwhp~NHF`6oB^ye7>m{RaZykrJZ+T4&tnUp&)qBHCm4Ms(m*BWe z0#mRaKYYM*@Db@h4{kWaZF2d_BhN0~16g`IJ4-G74PB0su zlvew42m=|R;thimROSb%?w8IVpuf}~sKdLk_W+cCKLm4V#wT;<$HUy6=n4JPkEbt@AZ78WcqJ1qVl^xnwavRZcsZ1^IoNQ0sGkW9zkgT{FS72tJ zro5_grN+TC!%Qw%xo+sv^=QiUBv;CurnT2-0yZ45_g|@*YRaH?Su>q_XhuLcsk3Uz zUsF-^3FYA{qUbbYXL3+2HkF}N>c!LWEZi`d+Xv)^m<}@wrk$~4^s=Vhoa9QmLDbVN z+4|ZD;(mM(tjommp_N!uYBZCtjTpJ8%q%#e^1EiAF$qbfQq$q;gBg*s%cGtOn%e`0G@h`FdYM`EyKH$_@5DimH0IC6v=K8?Nrx;kZoW+6m=wj4RC? zq8nEup*@OGnT-{Jt-tyc7dleDF}rXm|IWdvs8rbt0i0N^x3x zUm)`^T2}0b%HD0{45e5?`E6g?KD^%NkThjn+bd~`GMQtNRDS)Ish@EdOWhLqO6+Mr zqA8H==5VoeFjgu+Mdq2JhuDX9JN3t?7rtCYRuFn0F!c+m2!UB;tb&iVy!e1c>Uv;I z?tLJVipS6#&+33n;_#Y2)`DiU((VTY%r$6AP7JIz-1|UvKg_-`nfI3^F%KQ|l|1y6 zQ-ACh>Gr;XVOUHp!Mvej>AXzeOk%wVf^jHazDZQ&MhPk+VQL#v%aPt3Cjk(cIqck= zrrZXLlqD7SWr=Q)^yf-`Uzb`iFzumNYt>UfkdCV`aC8`EujoTUi}>^dR`K}Gw+^?ci%jh3yKM1;g9i2l%?)^!&VuZWjmtmZ1H8_? z{UKAJMO|#7HzS`@!Aj`_L0X601roJ`s6Um;bn5v&9;2S`r1HZzAXr!d{8V?Lboh#F z71m2v@`E7jr8nl-h*nkXe>X^TPLBKE5Ay5NcTm%oBJG!Epq!aJJ92z|I$tuCfkJhJ z?55cgm_Na!;ftV41WU8#S_knYrXxX`r>QsIz zT~lgbUyj=(l=9>^eh%;TZGXtq6HE&Jd$)Nt*gi`eutxe@d z^;5bq-}y|L!_;R=^#JNgnu^VR^nVqo%}GUiE4MGH@X3N9CXz=zoLRTj!ug{f9!CYGjd+^E00N@Ys8(TvO^F~)9=!pe0;Q0a>? z_CrCKyF|@shsr}iuw;4-qZw>o&6?T)vfZ9Klv?^*Th0mq0DM9&eG5geEq zF*13sS5(HHR31oh5iV;HzKMFHmgl7)KhP!}6Od)4t46M0*i#lW)UoWlBYJ zqC7>@-y~?(!nM)=cx@4G#1qQa@kQ8y7t1iaNv7lA*I@QNDZd%Lt2#w>NPIu_0l6iY zm?`B>dY=l!xXcG8lxN3**2B;G?(Ku}w}K!v6IiJq;)7r-3APbfNj(if`uct!;f+5T z=Kc!h8G}$+GzessdPe1j&I~hF?f~`rtQ%d4pt5+7-qXEYlm5Qi**fZC+w0O#APfH& z#N|5k6?K=|we&UiL3tW0YSX8&y8AL#M1MuAl)SFv_t4n$e_^O}kPgpd&KbDwlz)8t znA>+WA|Ty3n-s=Trsf4_#;N6n5YZNU2)peC zr{g?qW2%?etS#Lsb3TtBidr-*ghwmAND+j=NARyNisEV`T-vYm5#5g*;{Lv z9G^M1w-(Ny@|f^TqdZ5)9*{eo{3%!f#ODF?pN2ulr|v8s9PfxgxjVey$sFJAg!6r# z9YuGHvMdtzU|8@<=ug9N-S6b*9Y-Sq6Q-29&KFOTS>unWQ{$$bvT^48a}J2}6BVv$ z#@Z27`)VyW&PFp%{eseAk%#=s^J=Z*{7w&3y`ttfqefjIo{UV5=d49>KK5&W?TE4V zFWG7uE>lhOvw|KmNF5rmNEE8sTbQtYya0c^F4y8K+7{IW8lj+3SzJSc^}+9APrn z*Ss{E$sI~luLk1$`0xF-saAXn8Y0@#`Nv+Ytvtn4udi{8WH|Q5nMY}xrrJN@Rk-l@ z^w4d-gQHWK^`knD8#gGHaWpo|^%uIb_ko$N?ILW)MtLV5{nCWBFI}}?9y>hBOx-YQ z)S>Dj*@lnHIe4eM4fn}B-YoODL8iNEMNOVe_e+^fygmLW{aLOqXBNHpJ()qt zdVBnZE;N}d*q)HIMc9yPY|o8k>yuv$yE?>vjuf7_Bv-E|#=UShs-H&}eN>-@2jqx$G&;&(45A z3?R(oLHOE`j=>^wmBtjVi~!3tygdw7DsR=493jn`@XP^3=8aPeVGsRZ9x6k8Dp;Ov zdT!N?Dz}U?=kCkxVoA=#t4;=A2zNJi_|I(zD`T{Duw75Psh^qY0_#)t9}k0-AtzM5 z@MHr^Iwp|Wb@6$KE4#*<&c6n6<)v{QZaTjJ;>z>mj*(hGHZDYA_CQ>DXdLGLa@7%h z7{83^x91?P+&2zp*TqhVD{bS*yz=5x5LfOR2QqyE$an(Cjsy@#!nhBSM`GDMdZEW( z>B-)m({q0VOKK*76iqPXFKXt0Go)8V#H<2ANkn|fqs3g;y3tHl*9F!y!yLM+vD3*1 zw>t}uA@X9;!1Q99ezD|e#J`9VG7U{dzjWVnu zg_-_M+}K*n2XCp(JeIpJ>j^~iV*Tn`d)6~At6*O$-Xq@WolY3NkfI``(_n1bsuRQX z|0ew`gvjzFEvM(U`4}Qg5^?48*rhc%6HBkb8(}a9X z8RO`pF|NDNOdc@49w!$A@reuQDzx+u&ZmN4rmIB9d?7Zg@ej@%2}Kaf5#Ksl;x3ZV z;v%t6E~!V-igIsIFY2XP3!Vxt!hecluiOIG%63HdB@T@8EZ>#cQ`ER_ zlw~tg)aOx}a>3}?Kiu(H?!G>i6A!73=McRcL9SD$^~@Ugs=xQY?w>W@8Lz-d_;?r{ z%xb8@AFJTel$l9HewOgy%qQOZlAc2wogc-M2f_Y4@H7syV+8$)3&;BGeH@j$VXJYX;^06&v|-Py=T_8f5?=sl-A#~Q7pFODYzRi3H`)Y z8oJ6Rg~8fQ?1~giWzA6~-8*J!gcda9gNOq#f-P3qCj>| z2TZ=3ZKjj6Jndez$m4eq9@;%j)u_Dq|Eugv;G3$_zMpe%mfIw4(x!!Oz)eCSZ78HI zAX1bxX)kS32&=Lw>4F4g2^6&;4na_Z+W-{@s3=%@2gIc*;!qKS$heHlBrHx5uyq+P zO-H>cg?rPK=KGzbD9-oJ`+nd3{o0eWpYxn^o_p>&&+~r-HS9B|`!s?YP*F3x&-|<} z+nw$XvN#vjn(ih#=IP0{p>9+_6rE)EnXg~Wb_?uh=~2T9yK9=q_dzI1y&57Cunz8P z{`W$K$~y(Zp6P!tv{4D%yYBZwNNM6uxQTqZpUf8p!k(=ynxIJ3=SJgxYN0~W3E#5E zJ?Rqu{QK_f?4W$;{y8$8%g^j2FOH4H zt<4xU!Iv?-*%R_;nXN6quxlS*^EA-;6+2p@{6~E|Sj!DY{gV0lKwdf4-+!7tbB#_RY8@e@nHI8-fD2L%O)Y2daEq!{Ki z-T1*W*AkCQg1-vjrgZ9#cHyAgqy-KB4%pF$%Y3Bwpa8MFYkCg~L@Xt((>aFNhPsB> zhPiakSIn(vfi^hFt|_F!p>ckirNMG(PqhmRx8btV%KQ1{eRdA0zcKjM{bWBCLe#Mk zrOXuw`SrkG1=x3iRoD!U6Rg4(VHGyDBSZHEE4Qf~gLR*>GFyn1*)VP>rrA0Q=z0q1 z_bH&OUjZsR0qCbOA0mLp^u;vA^i>_TcBerv|Mz~nlD0a%O`dro*?GLfNHC}!(u)}R zjUE!^H%Cwh=+urTkGjXbYOpQSzrbU^5nZk32xVFKbdvIAFe#PzEv|EBlzeKLpN&x- zwT@o?>3*G4Y1rZeoz9^;G2gR8Dm}lzQ`S9ahMGglbRVhtj2)B|7RF<@`_9b$A-f?C+46! z2hr?0ky;8SQ7M={PXHQ9!Q@W>`iTUfA6o*{WGiU!{q)^a+XeW*;C!MP*J*I5>hG-w zZZi3D_6!%%#YkQ>OD?7esB2R&31tgNb%Xt*S?o9Ibgrnb$@RS}u>-hMVA2l>e;qw7sA3k9~V z73U=mldnhlN&TSz<`U6J?xqb}e6)^e(A5)rNNzIOV4mP38i9aKf=rykZ zg=vFnHQ{K6Ez>C~O5u`}Sx%{cP=!2(Rw8#GO{y)!bxtC=kYXEBpYO#;0#QCEcI%_8 zq@59dde|Q-g&x1cmQ|12OB6MCS(N`ehvQ7)JciKF&M0q=#_$eH!K5e!)Amw z+Udl4WLcFm8sn8AQs=<>FFL1;#&|8*#|SznqAeU1^Gz0X&MYZ$0dqpt37xZ+ws4|Y zOrbzKRh$Sy0m_zO&2$iKtNQx?`?mm*WQ(eAIAcQVd6?OYg3LQNxi5 zqY;4)^DcGerveyt&JNxEliA<6!-ZMydQf;(ivGtg0?b3S%hW;?dpb zux^>C1CKn;?{2{;Lg1?$j!a{RBNMI@KdHWUuk4ITb1L-C>dZA4t)SwW5Y`<;ug* z0M4YtSi%W$4bjJ$V_ubJ!jLE*5cUd_j9{4PFVxm}@L28@Ca55Hf*NtXIY&pZ)Igovfb?FG8FDC%~ z^M;L+SEZ1}*V4q$G4M{od>7Msav}*^WI!*J0sSHc^fnpB=K$^JouF&7WqH1L%ZH}> zkWShVmsXcH7JEgpFVNXSjR(u9*0_&*)LbfQ;_@~BZXf#PQBppT# z4OaQ#hH^~7#85toX-IH65jT^5WUr7<*LWZgxb1E{zn`%xcdMMqj!kBXFW#%z>WEQt zuQ1xUH$0lIHAvfvJUUK9;$2RWd!sGW4LWl-C4N&FYdr25Vp{2k9MF|?Q<67@@y6qx zp(fz=yI~~WMUs9>v$DLOzaGu;VqCfh%lr9Xq9eWb9+=@Q@8>(CI?sdCQVd&SRCn64 zJWXz#PZGelwq!usC~pxY>aUs z+l805;ku8T2gm9zXl}bNF;qkn4Jo?BP$BU}C$7H$C5Fb6h#S(2?!fgk9Fly`!sy98 z#c!Vw#v3uc6|owO(Y->EtHv|Ni$^@ZYI0dTv+iJO+{0NIc^7kxDPqCrkpXQSn7^1; zv?TzI=QHLX7=yepAwGxkSJH3ts14RjEoVE4CHTzdo}iT6HdP)t?0HE-UO@Eo75#j6 zl-4{~-p@lcs{^=)`a##+C84%jtGc8K@%6}_qc!>={rshVdk<9MUtjeX7-ElMJ zYcbz@?yzUBnFJ=s%b?uaFt=CxwHIf0aX3Gx!+tNru+G2{W#?;Z*jdYR+_w( z7)=Hid(t?SSmeiXFk_fQ%iEUU`;)qb^6x{*znNFB^rjyuprc?9~rYV;1&h&s@^fl%MgG<$=|75q7P4I1t zAq=FI-e7_I>UjKa9*>_Oh#35J)FZ$MJBKKdCDluf76)MX2!_U*2GocSs#n5~G$;6x z=Dil6f%~BsOCt;k4-ZO3X#9_?Dx^|UKA=?{)Tm@X)hpu1m}P#@Ax$QOC6Mm!%?V1y z7=iC@3mOagT>;D^;`*@wgq~zn@5tM-hu2uB%J1hEdClFby4_|;o9cbwTCfJR5$lPp z;xy39g71@kKmpft4AT?$;70 zxGnEt86-lV(3Y*6YZ2SB=7K@t!?%$*Jbo(~ug7(ih#`4{e()uHOQ?mpt@4UAgt~~- zig_rf)~P7nZx)@i2wK3gt`p*3bi-&t1=m=hdA273=&&;SRhAN?t8qEoQX++d5Iy_ULXtL`G(jq8Ep>Y^*yAx}@-$GNM z(cxKwD67C*xfB^oIV2+Wl~vaVblBs_Gq`R{ulQPt@@zlo7Y2+rJyRs4IikESDvIH* z4C10nD=vEgBh$`hQ&dDOjF^TPNf$-#an5!2^1xE<3WTU#hxX zwXo);n#(oWwb|7#)k^)ub*OGIlYZj5duD?mwEwG81B0*(TFvx)XBEy^jzH#5!Kgv32>nzV;PmzTT0+KU|;{`z}r25cE z7+EL`h9V0cM4%N0gL+dzP(mvG*>ss@m~H;Nc^O#F|6KKF&LI^?BB5)jxS<;9W>wM5 zh>my}q7g8nP#6U95(YsweUGQiQe>IsR@&yzo11~lOZR=~OscSR0O>wliZ{{|O7~%j z0u+iCr287G1Jzh&ERKJL*T=1KgOv3#y;`hazlp*65Y_#lFAGTWEp7NzP*hxGE-o$x z7>Pz48_;M$4HyfuoQd)e_rtcuM{*hb`|*Aev#qtzn#&Mf394-Zwa*?*$eJFrT99uQ zF`O3~)vY*XL;qeuG#$$c+`{qAv7!+~S3(MmJS&LYpRq8)IkK7gI5rwsIw?)m$;Nl8 zCML`;xS3&{U%Ep`IF+rnb5V+j$a>SPicqv@rXW+6ijYE4B8;Nb7y!y@CcmbAI$9Pb$ zG!JG#vs_Cayvav;AwSh;=Lr0zLPz@oT4_V{YYo$MDo80sYX#KmBO;?>E1B^QD30=IO3hsE~OqnX!O81Wi=r|HjZNw4DCC284(;aYjG z;u>zp%K~K_`Zf_E*JO`eWO-RgfO&${g(jGVg&Up%d9Sp0rm%d&l%P!Z6qtqOZ-`?d zP8=dN3(gJ1NNF$h&J-L2A&w0*h1v~NFZ9M!)NXjli$)QCw1>z`Xd}BmB!|9EmJ(f? z$!`RpEyCPUiV#vHg;Ys3F@50I*jsZL^K7gumc&GP@}`LKwBl8%zlrpOpBzRQu6nUm=0s8(C#4&OEVANyIw zPtYNPUNLANZ*IQ6eq%x#XlwN;ZJ?FuGul8)9VePyQ_v37c;tHTD&o?<>+4-X7B!+G z)X>A?@Q)4XO6`On2EuN{!qf(IMK}n< z4q^UEq$K99iiKoAm_HvWiMbENLL{+1mBifpVj)rp^QR*vF?V(>L>^i(G-$#me5&te!p`_juofbcor@KMN=E(4m9VZ8b%|Bq;8_w>Ro=~y!= z(N@w$h_jq^-gBLVP8BMYl!QR~ikb4gXqKHlY^Hp#n&E6JBeK2LlI<4RvK_*Su?)|u zWIzv<0X<<9G6_eMZCTD@ufLO6a;}pod)rL;{>v;mE3fF|#W%4uc9j3n_Y#A3(|?P< zaTdiSwH*wy_VN7t;KOBNY3{+y(A#z^{!T)twh(?H5^A{yVVV9b474wmU!YFlQ{au&On+J-v2Etw8eH=!G99_fF;ItYJ%ITu%M z<_J>lsI?7onz$F;rW+B^dfsd~oY~m2+5GUucHy-Tnw*yfpc~Bh`4?6!ESEVO%yz%r zA<~f!&^0-bPFI)Xu9KQVd))WfCVH|wb1Keef^J6({+7eiC7azdD`p5f8WolZIxKG_ zvvVMyHZ{tpMn^eg64ImA`OkL}y4_~Vx6NF44kLi~@sIVL?d$=pOg%6%d5N%4{EpKO%3HF-u> zoXf0s%iXWK3Efj{JUo06bXu#fPVI2BHJ-)puFS@krt9TvTCTsnD%AF>Q=RvUZ$|ch zM_PqONHLPS2U+}GyRm2O+eudSGE}6lUdKlH)_#1yDf|)7&ukgcs!_;9k3yzO8PH=# zAycUg=<Q#7(UBPw`rO53PTKkrI(-3ufbZ))oJBn zp6ZuqQf;Z$wDQy#Zt89a(y1#H4$@KTAZf}mn0~g}CeRMj;d4i=_{=8=q%f>7=%bnJb;L^{LEICdzC2iHt8g zW$X3K7oF7Bk}e5}zl5XwGbaJ8H(uA?vc(2QFv+dJNkQ%W;F=uaJ6*M-tb5K(Y;iO${KYy)PX-8GkqgmS-?NuB>mzNTb=h{gT((RXsSB|yY%8p7 zE_FRBQoBUDPIg&^(<-m`r|+moMVDI8#0K-nF1hQQfLM2lt+7>AX4G#HN&yvo+OjV@ z!-bK6kC{!}n{KuqjhX8w#sGK7jrF$n@Ms@yTWO?(L0lw)IP^cX@ReBF(Xq7uj3BP7FWwtM@fj@`Q!=36Qvm&e4Cqfk`Q+}yufKjbr7P*y5bhwNRXt$02ThRfn{GnI?v@+a z+6bOE_7&5fY8EvV)r*+zjOvvWLg_woyVNkEt^KN+qrd>uU^VOm4&H&&P-CB1pW>}4 zN8GF7gQHB`j!h^BXa~kHb}h0EaV@f?$NsSWtNU%^T%U!Cj<_eo zVRn-q`H?=WZKiFZYo={fYqo2)Rb8(uRlBH;ta>o;e*07nqxVGlSE711o~LCt9Ddoa zVJgcnvv};kVmA*RY6!QL*mk)}Y+3b(z2>PXmgkA6-hG!fK65cz@%UKYlYT9uVeTr& zcx=bm308GIS*msg*&>_KKBRsZvp&P`8e>hVKkaQ7PHjU>s{jz?7ex;V0Poc=&Hl7y zxXs&TR%X?E1W?H?gJGv%%jA_4cV1v~el1O;Ep&mwA+*hHbN8fkC#c`XX

x;#aOI5M1S%c_@q#k$?BME56FY1=H60={`OcvU!E{or!Mae`F0m8EQ(g)$Jw zdhw$lG0EkK`(F5#JuL(J6B*E#_XCB;eFFjXhcci)mH~Z62J}ZVpnLZNHS|@WN?rwO z$*Vv;`zlcHz6#WLuL70S1k`-nf{OHd4=a6kWEaxyF+UbSx@QD1;h{vr(K}7 zt6hidMSEtIed2pUAokfgk?e52+Wq>vu633mp}V9icIT~saDDvuqwc(Q4-SMMcfY>A zYao22Aenr)epcD|i?|&a@pG0}`)JLh<%}grXg*ba(Fw_z3rrMnC^0r(+DL(z{5_j( zdqQALdEU%=4U<`pIK42~wo_o}ton^?qX0%QxC8OttIH9Wf%U^Wz_7!gT>dy4=TLFo zLXyU3Xn1_^c;T_a<8x;dP&=A{dbtTGJZ@h$0fon`wh1W7Ye2o*1QZ_2&L)h}A{v^= zY;7KXX(@xaB|=JtlL_-zBShme#?rH|4$IFI4TxJLdyl48L6BKD$ z&=3bv!$PKy-x5JNn7g+N&HLKQrd&K8QYlOQcL-S^?m92t*S*Y$IBhQ;6|aDKr8A7U zmA$6!=o)v+HnZNRV!ow5=qgc*x;`XD%ug-Uq4Erskez+0Mbu07l>`+CgzRkUkTaVq zRSDUje;A@rX)g->8guYaHY)uvqykY%vXHHi7l|xL$gY%!kocQ+D!oc#pj<-j`Dx-;q#3XLaF;)`V|BiOWN){BFY8sBX=Rz(eE&IM^m<& zhxonMqZ_YZ#29Vc&7|LSBf4h0`KLf$y)w_lwYiZ_>oRpmlV4&onL!L1=Vy`5bR)X@ zB?dd+|0?r&b0K5u zZg!tuhzdYJh8wKz52=PpZAgQ9$!jR2O3pAr?)Uyy21fkFJno`G3-tXq*hWMog*yZy zrq__YICogl2;Iw!I$;o?@t?CK_X|1P@Ot2{?6FX?GWDWrOiIAi{bil0`^Um>AG32Q z3CSE%V%x4NCYd9YluyklUN&y2+mhJWB*3=sA5(J_LHdy{X^+|^?oe|gGVD)k%yc20 za*wGys!_X;4zzfj7O~js&*U2qz5Oc%wG#&@i0Q|)j;L3TCIV^()7#D=1;Y|~y%$H+ zlcO{JS-;X0Q~#IS^1Jvzu1G6pkLk(S0`Sgetj#Mul%d^) z?Q8Zmhae&MN|gUVNVA^pgu;(92X4Qm_MY|C@%uFDtkRb0%)?S34m`IMHhd$w*7!vy zl!+T;HtFl4hU~^KI*H9TCdzyI)9^aj3^6`-dz)~3nyZ2u}XtD0D0usQJvg{wYcIqzK=~#n+&I_N-pO2*hp%e9a1=9SWe|Q2>2R0d%9!|A8y}R z1<*zX&=V9ubFpuzgi4(g4CL3CbFYffjwpXFisg0oMX6TW8LuWtBV^#LZBa8Ct(;_-N&1%6y4E`Kw_S90TNz`q6lgZE(g8|Kun>*;>J zu^-EFJ`Dm-N3g%4ALqpW^avW;#bP_k-?I}=;JT6SZxrIB2&0#5UMM%G`cOp->S~qL5qMTGGXjM!yBko0g*+G$Vjvw^*_$O7^Ig}I-;1p;S zOd^xiD;Cm&3T2%iMy>Tj-Xng{KNL{py~v2MlrX1AY8O5^HAx_zITj+7&WmW=TV;G3 z%7NTkKa8plC~`f_Yw?s+yRf$7Zh>fQ4Ux(@7xCF~N7;=w%*k<#sQ9D+9d%{4%P^`U zAj+L`5%cy^zg(Mc%W%tVnT~!wd~;BY4;WdhRmLD16{P0AjBN<9;G2$lfmsQ7ZJ&P) zsK+MnjPWzfe=twNd&Ymf1{7ZRm^Wdbh4~ZaS(p!CK7x6eqBWO6!_m0Ze0KnbKfyxI zE-b60c!MpjNbo#krY=ut73GO9=6EOAGTk!m9X2l;r#H%%-HiSy&)?W{^DW8iiJ?IV zW5I&{YM|#wq)iOb3Po2yku8Y+g*Yim^pe*s!6Z_hs}Mw!I@*ZF-R3K2QSLB5kxToN zTL~SWQG10!bc&7aBGeyt!jcn0I-R*Gz796_w7hj7Bq#4P-&cYf5k16}fN8qqu^*ok z2EljibHX6HodqAJ5vB{KC+3fszL>{|m}i(Y2I$ghW%ehUi7rw$r_AIpa;6(FN>!1g z*i~F_^CH6#KhS6#$EplB2Er%C-lgvh$dWzSMI@ATdkW*yE1hSNF0a1WRpcnJWxBp& z3!OU!=$Mr~xcJh9W zPY9Jp<(^c7-j}L7V%GbL7_}R;s;Ld;1pnx*qrFMHHA0F56{^NvXN^oR8+#|&;ua&~ z?{)k>!tWD2m+*YU^uzNF(+{67J=wgQd7RnCD4Bk~p)YwFzQdxm1q{Y5Ixdhy)2<}# z(KBk7a*u`?D=PHB$ZsK^y-!tdmEhwFGl)Y#VH^zdqF`jd&f})gAS!J5nj{}deNmk zMiVQ$BZ^U-u@3jo1GR{6s|BNpikz=Wr583kZQiV<#okN*q4YFH!OZibLlOS`&D+aw zkCl(_czan~OK_l;vwgQ~iep^fM5fiNYNcF2Qyt)((5h!dF*`1-u+OP)op2(`|0@dm zYhQ<1JwsLicS*q3CDQ=g9-4aqV|;<3z^}~3I}yZD@*xFdM;8>Rh82t*JGvk@*$Ld8 z$4G3wUYE|erX)KHI7AK$5Y7y*xyM~iIIgkU9(Q#wOFDmMQ=Fue;QWM+^OI@|KI#8~ zHFYZsQk+p9>j_ijWn4FTkzK{zOMdllBm3TMBa3k>o@!QU6EWhMCc@|S(F}1Y!lQoC zPB3@TMI#-ozTXUq^Vo=^*D!ReM|rrCm)emtn6 zF}}{i13)R?Q6CjysR$ct04^!4VbGpbBXF4l)?-weu*S0SXeu*=kugs-&+uY93=zII z9Ge9PBmAZ?M#{jyR)%|6<5B!2@I*6WFsezGfKxdc94Brz4vdwa`PK=XLqJB--{eF^ z*iMtcvk}rMGH}?wJN$;VcB+#oa82>P7{_A6xDyH{!oL}*8fr*Sj@hHjbYWBqY>Vy& zD?KW~lH(;9?Evk-w)bj;TXu<_C4m0@D!O_bt!0d<8zo2ixhFA}(jX?0xzh{WWP!*h z1NdYExDi6(fNf%X&!*K;-g5GeqcY|>K?->OC5EJcWsK4V(2FkPbB(wK3)!gNz~S`^ zq7DasuPYV%&}4G1;IvF2t#8AJ5uY zJjj5Uq|0C+7}X_td3p&li~aTw157H|gnQ4kcA&o#xuy=cMs%>daQ(}Re>VK}X<1AMpq$uWAx@gNojk%I7T zVGskfg?raR`Iv9 z5uyp43dc_mR^r)wD?T=R&5(4qCDd=1pR;o>lSjHzsuRxJgP^l;VA1swT&$JgnvxQ# zip@J>KuQqz1j`DVlCVxKGJyh_K!r?@icDi_7e73vX4T5NRm&Gc%(Hgwx>?5Ge%1qi z=xqQrjex!@9jF6?feH-*>f9ipqG>=4NdxMRG@urz0ToLP0PE6#dM*v9O#^>d(t*lI z|9!qs(|}r?2GoOt|8u^oH7g#zBY(x1sx>PXIjh#xK2Y`0^0lLDZdC(?0Du6%1^@&A ztONiO0Gr-0B|Y=Kmh>m z9Dqbzn++fdyDtJLvHL9mQUSne1O#@skU(OWl7a{eaPF6a82kT5fdsp%B#^2gCig~R z{|m{GpaO7wKL}(h0QZ)mAXfqG%NYR*6~L*F@*z(P6o9Ta~`7W?lRWr)YDaQ=YhDh;;x*BplA zKnw(sU;+v#NWpVJnv{^8m6A4L^7w+`y1abXBY#-8{K4wQ<#wiI_N@8$b+A8o_C>m{ zx3zy2IP>A(zS#Dsmv=w=%;QfSeEYxlzjNfh6Ca=Y^vg?^FPx1Ep&Q@-@Kf+F&8;U7 zzj5HzKYBJj+3>>NJtOJd(Z!R-6%I>J9z==~W%o{>cfYN&%)H83^+4U)$JTFs{wep) z9gQz}-}N1P^Yy0J!u>q=&+oea^}$Df|K!To=gu!(xy13%nnyRxxM$Jasa8vA#?Zkk zF(FrIMvT$lHL+;yvq&jo;e zIDjC=VrMP@!hS*|ng9Ula{HAO=_+5KBP@QM`0O4pC4Hl&>I%LE=F9i4qc$AWA3!$&_d#s0PYc ziIk8$P=2x$K?+2X8ps4SF&R<^%1;$bA#I?10I20$s~n5&zi;7!`Sa%9d(WKN zvu4h)Pn&A9R!m_^%_WoXD!%iMv4vyu^G53E>~wWvtjquFGiD&gi$>`qqpFgAes4y? z?u;`lq<`#L<{EdPrn6~h?aPIpOG&RCyS#2_=Y#j}4hRKA;VVuSY&()?rW_94D) zwW_}i>86{Pm9K8S_D#vjEsvf5IT>36X!PHvunBf)WHX9*N3Zb{_E4l zPumxw)Qig{H8poBd#@)_&wWC#EWTg0wDN}%$AvYkm%JMIft)nuyvTO*iNv!H9+e&F zJ$Q87@?9N3 zN-jSvS$zq;PoLeDr@HXV)+fBHhaG)aa^MHwD@EszU48XaY5mwRD4#!=@M8L|q;HQW zF58%Y*9z)S%WJozg*89+%y{s@>Z;}0ZN|kdbmsiUUsU?fA!N~_O4;k5Zb-Z`X|;Iz z>m|fUl}di{Nm}t~&Qa&RN1j+kC!Bwv^_3s0zDx>#bN{YSFXn1@`J3N4_>YeV-*sf( zro?wf7cV^Vmp7NccZ%M8?5B5+`1UBidzajE*1Pu3DHnooKXP_&+K5Y{&4Vu2rO0c( z-%?!r!rjYOBp#f!S?BvZ4Cl7aU;nl0bL*8QtJ+(`;a^TZZ#nsw!55xyc3f@x>Z?CA z1oodf-8Nxnce_2b0m70J=bw(%|HUmFtJDzjv7->{P79qUCUAO7NKpVPkN z;4jawELeAPDf8@+s?RbvKk)v(v#WB(f9IUJ^AW}8~}x<-93h#$B5cBZaB_T5_s@1qm4-c>X{e|AUW$qWDd%P*HVXxcBy&!0W_r1`t^ zA>qgs=gQ4r5Bp-!$xRDJwBGpkk>*v8O!-UtkMk*yYnd|ow_?cy3*{&|`tssGE`6(7 zI2V1es_gH}2i1Qk+xPR?#DC1*ESh%u2zh7Kh$VmK2RZyxr!1|w^vKG)t;+&$U7r8d z#Ruf=Ca$>cj#+QLf9S6-AOB|K-&>}1Mvoe^yHA{W`t*B$Gd3KV^T00ztqkA-`4_|VB4?1fB#T>V|$#~{`dcWsMtP#9F7>j62SyyN|*~E+c&T;x$W`) zhw^`WOfa3iRgVc&zyALH<9`V#{LS_I&|6QuJ>#(#x2F_L#9ROp?}h%q9}{rDw!sA3 ze*OLX2h#_C|NTDn))Q~f9oUQ8Qx2xgxd2&s?{q84z~jf|XJHS4w`8#gWdo$%<|l># z=x_6rLjfk;<`)eEn0}jIOas*3=9g#y>TmON7=s?)D+9p8xAu}y2%mszaR>vMZ({J~|K#sfr^5KjjH{|A_S_doyu literal 0 HcmV?d00001 diff --git a/boards/nxp/fmurt1062-v2/firmware.prototype b/boards/nxp/fmurt1062-v2/firmware.prototype new file mode 100644 index 0000000000..f03a47c381 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 31, + "magic": "PX4FWv1", + "description": "Firmware for the NXPFMURT1062v2 board", + "image": "", + "build_time": 0, + "summary": "NXPFMURT1062v2", + "version": "0.1", + "image_size": 0, + "image_maxsize": 7340032, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/nxp/fmurt1062-v2/init/rc.board_defaults b/boards/nxp/fmurt1062-v2/init/rc.board_defaults new file mode 100644 index 0000000000..ba812e4b7b --- /dev/null +++ b/boards/nxp/fmurt1062-v2/init/rc.board_defaults @@ -0,0 +1,21 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# Mavlink ethernet (CFG 1000) +param set-default MAV_2_CONFIG 1000 +param set-default MAV_2_BROADCAST 1 +param set-default MAV_2_MODE 0 +param set-default MAV_2_RADIO_CTL 0 +param set-default MAV_2_RATE 100000 +param set-default MAV_2_REMOTE_PRT 14550 +param set-default MAV_2_UDP_PRT 14550 + +param set-default SENS_EN_INA238 0 +param set-default SENS_EN_INA228 0 +param set-default SENS_EN_INA226 1 + +param set-default SYS_USE_IO 1 + +safety_button start diff --git a/boards/nxp/fmurt1062-v2/init/rc.board_mavlink b/boards/nxp/fmurt1062-v2/init/rc.board_mavlink new file mode 100644 index 0000000000..efefc2beff --- /dev/null +++ b/boards/nxp/fmurt1062-v2/init/rc.board_mavlink @@ -0,0 +1,7 @@ +#!/bin/sh +# +# board specific MAVLink startup script. +#------------------------------------------------------------------------------ + +# Start MAVLink on the UART connected to the mission computer +mavlink start -d /dev/ttyS3 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z diff --git a/boards/nxp/fmurt1062-v2/init/rc.board_sensors b/boards/nxp/fmurt1062-v2/init/rc.board_sensors new file mode 100644 index 0000000000..06d215a211 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/init/rc.board_sensors @@ -0,0 +1,90 @@ +#!/bin/sh +# +# PX4 FMUv5 specific board sensors init +#------------------------------------------------------------------------------ +# +# UART mapping on NXP FMURT1062: +# +# LPUART7 /dev/ttyS0 CONSOLE +# LPUART2 /dev/ttyS1 GPS +# LPUART3 /dev/ttyS2 TELEM1 (GPIO flow control) +# LPUART4 /dev/ttyS3 TELEM2 (UART flow control) +# LPUART5 /dev/ttyS4 EXT2 +# LPUART6 /dev/ttyS5 PX4IO +# LPUART8 /dev/ttyS6 GPS2 +# +#------------------------------------------------------------------------------ + +set HAVE_PM2 yes + +if ver hwtypecmp V5X005000 V5X005001 V5X005002 +then + set HAVE_PM2 no +fi +if param compare -s ADC_ADS1115_EN 1 +then + ads1115 start -X +else + board_adc start +fi + + +if param compare SENS_EN_INA226 1 +then + # Start Digital power monitors + ina226 -X -b 1 -t 1 -k start + + if [ $HAVE_PM2 = yes ] + then + ina226 -X -b 2 -t 2 -k start + fi +fi + +if param compare SENS_EN_INA228 1 +then + # Start Digital power monitors + ina228 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina228 -X -b 2 -t 2 -k start + fi +fi + +if param compare SENS_EN_INA238 1 +then + # Start Digital power monitors + ina238 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina238 -X -b 2 -t 2 -k start + fi +fi + + #FMUv5Xbase board orientation + +# Internal SPI BMI088 +bmi088 -A -R 4 -s start +bmi088 -G -R 4 -s start + +# Internal SPI bus ICM42688p +icm42688p -R 6 -s start + +# Internal SPI bus ICM-20602 (hard-mounted) +icm20602 -R 8 -s start + +# Internal magnetometer on I2c +bmm150 -I start + + +# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer) +ist8310 -X -b 1 -R 10 start + +# Possible internal Baro + +# Disable startup of internal baros if param is set to false +if param compare SENS_INT_BARO_EN 1 +then + bmp388 -I -a 0x77 start + bmp388 -X -b 2 start +fi +unset HAVE_PM2 \ No newline at end of file diff --git a/boards/nxp/fmurt1062-v2/nuttx-config/Kconfig b/boards/nxp/fmurt1062-v2/nuttx-config/Kconfig new file mode 100644 index 0000000000..19906a5c81 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/nuttx-config/Kconfig @@ -0,0 +1,41 @@ +# +# For a description of the syntax of this configuration file, +# see the file kconfig-language.txt in the NuttX tools repository. +# + +choice + prompt "Boot Flash" + default NXP_FMURT1062_V3_HYPER_FLASH + +config NXP_FMURT1062_V3_HYPER_FLASH + bool "HYPER Flash" + +config NXP_FMURT1062_V3_QSPI_FLASH + bool "QSPI Flash" + +endchoice # Boot Flash + +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-8, as PROBE_1-8 to provide timing signals + from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-8 as PROBE_1-8" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-8, as PROBE_1-8 to provide timing signals + from selected drivers. + +config BOARD_FORCE_ALIGNMENT + bool "Forces all acesses to be Aligned" + default n + + ---help--- + Adds -mno-unaligned-access to build flags. to force alignment. + This can be needed if data is stored in a region of memory, that + is Strongly ordered and dcache is off. diff --git a/boards/nxp/fmurt1062-v2/nuttx-config/include/board.h b/boards/nxp/fmurt1062-v2/nuttx-config/include/board.h new file mode 100644 index 0000000000..1f4d69b305 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/nuttx-config/include/board.h @@ -0,0 +1,430 @@ +/************************************************************************************ + * nuttx-configs/nxp_fmurt1062-v2/include/board.h + * + * Copyright (C) 2018,2022 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __NUTTX_CONFIG_NXP_FMURT1062_V2_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_NXP_FMURT1062_V2_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +/* Set VDD_SOC to 1.3V */ + +#define IMXRT_VDD_SOC (0x14) + +/* Set Arm PLL (PLL1) to fOut = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR + * 576Mhz = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR + * ARM_PLL_DIV_SELECT = 96 + * ARM_PODF_DIVISOR = 2 + * 576Mhz = (24Mhz * 96/2) / 2 + * + * AHB_CLOCK_ROOT = PLL1fOut / IMXRT_AHB_PODF_DIVIDER + * 1Hz to 600 Mhz = 576Mhz / IMXRT_ARM_CLOCK_DIVIDER + * IMXRT_ARM_CLOCK_DIVIDER = 1 + * 576Mhz = 576Mhz / 1 + * + * PRE_PERIPH_CLK_SEL = PRE_PERIPH_CLK_SEL_PLL1 + * PERIPH_CLK_SEL = 1 (0 select PERIPH_CLK2_PODF, 1 select PRE_PERIPH_CLK_SEL_PLL1) + * PERIPH_CLK = 576Mhz + * + * IPG_CLOCK_ROOT = AHB_CLOCK_ROOT / IMXRT_IPG_PODF_DIVIDER + * IMXRT_IPG_PODF_DIVIDER = 4 + * 144Mhz = 576Mhz / 4 + * + * PRECLK_CLOCK_ROOT = IPG_CLOCK_ROOT / IMXRT_PERCLK_PODF_DIVIDER + * IMXRT_PERCLK_PODF_DIVIDER = 1 + * 16Mhz = 144Mhz / 9 + * + * SEMC_CLK_ROOT = 576Mhz / IMXRT_SEMC_PODF_DIVIDER (labeled AIX_PODF in 18.2) + * IMXRT_SEMC_PODF_DIVIDER = 8 + * 72Mhz = 576Mhz / 8 + * + * Set Sys PLL (PLL2) to fOut = (24Mhz * (20+(2*(DIV_SELECT))) + * 528Mhz = (24Mhz * (20+(2*(1))) + * + * Set USB1 PLL (PLL3) to fOut = (24Mhz * 20) + * 480Mhz = (24Mhz * 20) + * + * Set LPSPI PLL3 PFD0 to fOut = (480Mhz / 12 * 18) + * 720Mhz = (480Mhz / 12 * 18) + * 90Mhz = (720Mhz / LSPI_PODF_DIVIDER) + * + * Set LPI2C PLL3 / 8 to fOut = (480Mhz / 8) + * 60Mhz = (480Mhz / 8) + * 12Mhz = (60Mhz / LSPI_PODF_DIVIDER) + * + * Set USDHC1 PLL2 PFD2 to fOut = (528Mhz / 24 * 18) + * 396Mhz = (528Mhz / 24 * 18) + * 198Mhz = (396Mhz / IMXRT_USDHC1_PODF_DIVIDER) + */ + +#define BOARD_XTAL_FREQUENCY 24000000 +#define IMXRT_PRE_PERIPH_CLK_SEL CCM_CBCMR_PRE_PERIPH_CLK_SEL_PLL1 +#define IMXRT_PERIPH_CLK_SEL CCM_CBCDR_PERIPH_CLK_SEL_PRE_PERIPH +#define IMXRT_ARM_PLL_DIV_SELECT 96 +#define IMXRT_ARM_PODF_DIVIDER 2 +#define IMXRT_AHB_PODF_DIVIDER 1 +#define IMXRT_IPG_PODF_DIVIDER 4 +#define IMXRT_PERCLK_CLK_SEL CCM_CSCMR1_PERCLK_CLK_SEL_IPG_CLK_ROOT +#define IMXRT_PERCLK_PODF_DIVIDER 9 +#define IMXRT_SEMC_PODF_DIVIDER 8 + +#define IMXRT_LPSPI_CLK_SELECT CCM_CBCMR_LPSPI_CLK_SEL_PLL3_PFD0 +#define IMXRT_LSPI_PODF_DIVIDER 8 + +#define IMXRT_LPI2C_CLK_SELECT CCM_CSCDR2_LPI2C_CLK_SEL_PLL3_60M +#define IMXRT_LSI2C_PODF_DIVIDER 5 + +#define IMXRT_USDHC1_CLK_SELECT CCM_CSCMR1_USDHC1_CLK_SEL_PLL2_PFD0 +#define IMXRT_USDHC1_PODF_DIVIDER 2 + +#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20 + +#define IMXRT_SYS_PLL_SELECT CCM_ANALOG_PLL_SYS_DIV_SELECT_22 + +#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20 + +#define BOARD_CPU_FREQUENCY \ + (BOARD_XTAL_FREQUENCY * (IMXRT_ARM_PLL_DIV_SELECT / 2)) / IMXRT_ARM_PODF_DIVIDER + +#define BOARD_GPT_FREQUENCY \ + (BOARD_CPU_FREQUENCY / IMXRT_IPG_PODF_DIVIDER) / IMXRT_PERCLK_PODF_DIVIDER + +/* Define this to enable tracing */ +#if CONFIG_USE_TRACE +# define IMXRT_TRACE_PODF_DIVIDER 1 +# define IMXRT_TRACE_CLK_SELECT CCM_CBCMR_TRACE_CLK_SEL_PLL2_PFD0 +#endif + +/* SDIO *****************************************************************************/ + +/* Pin drive characteristics */ + +#define USDHC1_DATAX_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) +#define USDHC1_CMD_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) +#define USDHC1_CLK_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_SPEED_MAX) +#define USDHC1_CD_IOMUX (IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) + +#define PIN_USDHC1_CMD (GPIO_USDHC1_CMD_1 | USDHC1_CMD_IOMUX) /* GPIO_SD_B0_00 */ +#define PIN_USDHC1_DCLK (GPIO_USDHC1_CLK_1 | USDHC1_CLK_IOMUX) /* GPIO_SD_B0_01 */ +#define PIN_USDHC1_D0 (GPIO_USDHC1_DATA0_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_02 */ +#define PIN_USDHC1_D1 (GPIO_USDHC1_DATA1_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_03 */ +#define PIN_USDHC1_D2 (GPIO_USDHC1_DATA2_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_04 */ +#define PIN_USDHC1_D3 (GPIO_USDHC1_DATA3_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_05 */ +#define PIN_USDHC1_CD (GPIO_USDHC1_CD_2 | USDHC1_CD_IOMUX) /* GPIO_B1_12 */ + +/* Ideal 400Khz for initial inquiry. + * Given input clock 198 Mhz. + * 386.71875 KHz = 198 Mhz / (256 * 2) + */ + +#define BOARD_USDHC_IDMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV256 +#define BOARD_USDHC_IDMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(2) + +/* Ideal 25 Mhz for other modes + * Given input clock 198 Mhz. + * 24.75 MHz = 198 Mhz / (8 * 1) + */ + +#define BOARD_USDHC_MMCMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8 +#define BOARD_USDHC_MMCMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1) + +#define BOARD_USDHC_SD1MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8 +#define BOARD_USDHC_SD1MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1) + +#define BOARD_USDHC_SD4MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8 +#define BOARD_USDHC_SD4MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1) + +/* LED definitions ******************************************************************/ +/* The nxp fmutr1062 board has numerous LEDs but only three, LED_GREEN a Green LED, + * LED_BLUE a Blue LED and LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* PIO Disambiguation ***************************************************************/ +/* LPUARTs + */ +#define LPUART_IOMUX (IOMUX_PULL_UP_22K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_SLOW | IOMUX_SPEED_LOW | IOMUX_SCHMITT_TRIGGER) + +/* GPS 1 */ + +#define GPIO_LPUART2_TX (GPIO_LPUART2_TX_1 | LPUART_IOMUX) /* GPIO_AD_B1_02 */ +#define GPIO_LPUART2_RX (GPIO_LPUART2_RX_1 | LPUART_IOMUX) /* GPIO_AD_B1_03 */ + +/* + * Telem 1 has RTS as a GPIO HW HS signals. + */ + +/* Telem 1 */ + +#define HS_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_SLEW_SLOW | IOMUX_DRIVE_HIZ | IOMUX_SPEED_MEDIUM | IOMUX_PULL_UP_47K) +#define HS_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_PULL_KEEP) + +#define GPIO_LPUART3_TX (GPIO_LPUART3_TX_3 | LPUART_IOMUX) /* GPIO_B0_08 */ +#define GPIO_LPUART3_RX (GPIO_LPUART3_RX_3 | LPUART_IOMUX) /* GPIO_B0_09 */ +#define GPIO_LPUART3_CTS GPIO_LPUART3_CTS_2 /* GPIO_EMC_15 GPIO4_IO15 */ +#define GPIO_LPUART3_RTS (GPIO_PORT4 | GPIO_PIN24 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | HS_OUTPUT_IOMUX) /* GPIO_EMC_24 GPIO4_IO24 (GPIO only, no HW Flow control) */ + +/* Telem 2 */ + +#define GPIO_LPUART4_TX (GPIO_LPUART4_TX_2 | LPUART_IOMUX) /* GPIO_EMC_19 */ +#define GPIO_LPUART4_RX (GPIO_LPUART4_RX_2 | LPUART_IOMUX) /* GPIO_EMC_20 */ +#define GPIO_LPUART4_CTS (GPIO_LPUART4_CTS_1 | LPUART_IOMUX) /* GPIO_EMC_17 */ +#define GPIO_LPUART4_RTS (GPIO_PORT4 | GPIO_PIN18 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | HS_OUTPUT_IOMUX) /* GPIO_EMC_18 GPIO4_IO18 (GPIO only, no HW Flow control) */ + +/* EXT22 */ + +#define GPIO_LPUART5_TX (GPIO_LPUART5_TX_2 | LPUART_IOMUX) /* GPIO_EMC_23 */ +#define GPIO_LPUART5_RX (GPIO_LPUART5_RX_1 | LPUART_IOMUX) /* GPIO_B1_13 */ + +/* PX4IO For RC INPUT to FMUM (without PX4 IO on Base) the Base must be modified + * to deliver RC INPUT to GPIO_LPUART6_TX on PAB-X1-72 (mates with J3-72).*/ + +#define GPIO_LPUART6_TX (GPIO_LPUART6_TX_2 | LPUART_IOMUX) /* GPIO_EMC_25 */ +#define GPIO_LPUART6_RX (GPIO_LPUART6_RX_2 | LPUART_IOMUX) /* GPIO_EMC_26 */ + +/* CONSOLE */ + +#define GPIO_LPUART7_TX (GPIO_LPUART7_TX_1 | LPUART_IOMUX) /* GPIO_EMC_31 */ +#define GPIO_LPUART7_RX (GPIO_LPUART7_RX_1 | LPUART_IOMUX) /* GPIO_EMC_32 */ + +/* GPS2 */ + +#define GPIO_LPUART8_TX (GPIO_LPUART8_TX_2 | LPUART_IOMUX) /* GPIO_EMC_38 */ +#define GPIO_LPUART8_RX (GPIO_LPUART8_RX_2 | LPUART_IOMUX) /* GPIO_EMC_39 */ + +/* CAN + * + * CAN1 is routed to PAB. + * CAN2 is routed to PAB. + * CAN3 is routed to PAB. + */ +#define FLEXCAN_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MEDIUM) + +#define GPIO_FLEXCAN1_TX (GPIO_FLEXCAN1_TX_1 | FLEXCAN_IOMUX) /* GPIO_AD_B1_08 */ +#define GPIO_FLEXCAN1_RX (GPIO_FLEXCAN1_RX_2 | FLEXCAN_IOMUX) /* GPIO_B0_03 */ + +#define GPIO_FLEXCAN2_TX (GPIO_FLEXCAN2_TX_1 | FLEXCAN_IOMUX) /* GPIO_AD_B0_02 */ +#define GPIO_FLEXCAN2_RX (GPIO_FLEXCAN2_RX_1 | FLEXCAN_IOMUX) /* GPIO_AD_B0_03 */ + +#define GPIO_FLEXCAN3_TX (GPIO_FLEXCAN3_TX_3 | FLEXCAN_IOMUX) /* GPIO_EMC_36 */ +#define GPIO_FLEXCAN3_RX (GPIO_FLEXCAN3_RX_1 | FLEXCAN_IOMUX) /* GPIO_AD_B0_11 */ + +/* LPSPI */ + +#define LPSPI_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MAX) + +#define GPIO_LPSPI1_MISO (GPIO_LPSPI1_SDI_1 | LPSPI_IOMUX) /* GPIO_EMC_29 */ +#define GPIO_LPSPI1_MOSI (GPIO_LPSPI1_SDO_1 | LPSPI_IOMUX) /* GPIO_EMC_28 */ +#define GPIO_LPSPI1_SCK (GPIO_LPSPI1_SCK_1 | LPSPI_IOMUX) /* GPIO_EMC_27 */ + +#define GPIO_LPSPI2_MISO (GPIO_LPSPI2_SDI_1 | LPSPI_IOMUX) /* GPIO_EMC_03 */ +#define GPIO_LPSPI2_MOSI (GPIO_LPSPI2_SDO_1 | LPSPI_IOMUX) /* GPIO_EMC_02 */ +#define GPIO_LPSPI2_SCK (GPIO_LPSPI2_SCK_1 | LPSPI_IOMUX) /* GPIO_EMC_00 */ + +#define GPIO_LPSPI3_MISO (GPIO_LPSPI3_SDI_1 | LPSPI_IOMUX) /* GPIO_AD_B1_13 */ +#define GPIO_LPSPI3_MOSI (GPIO_LPSPI3_SDO_1 | LPSPI_IOMUX) /* GPIO_AD_B1_14 */ +#define GPIO_LPSPI3_SCK (GPIO_LPSPI3_SCK_1 | LPSPI_IOMUX) /* GPIO_AD_B1_15 */ + +#define GPIO_LPSPI4_MISO (GPIO_LPSPI4_SDI_1 | LPSPI_IOMUX) /* GPIO_B1_05 */ +#define GPIO_LPSPI4_MOSI (GPIO_LPSPI4_SDO_2 | LPSPI_IOMUX) /* GPIO_B0_02 */ +#define GPIO_LPSPI4_SCK (GPIO_LPSPI4_SCK_1 | LPSPI_IOMUX) /* GPIO_B1_07 */ + +/* LPI2Cs */ + +#define LPI2C_IOMUX (IOMUX_SPEED_MEDIUM | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | GPIO_SION_ENABLE) +#define LPI2C_IO_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | IOMUX_PULL_NONE) + +#define GPIO_LPI2C1_SCL (GPIO_LPI2C1_SCL_2 | LPI2C_IOMUX) /* GPIO_AD_B1_00 */ +#define GPIO_LPI2C1_SDA (GPIO_LPI2C1_SDA_2 | LPI2C_IOMUX) /* GPIO_AD_B1_01 */ + +#define GPIO_LPI2C1_SCL_RESET (GPIO_PORT1 | GPIO_PIN16 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_00 GPIO1_IO16 */ +#define GPIO_LPI2C1_SDA_RESET (GPIO_PORT1 | GPIO_PIN17 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_01 GPIO1_IO17 */ + +#define GPIO_LPI2C2_SCL (GPIO_LPI2C2_SCL_1 | LPI2C_IOMUX) /* GPIO_B0_04 */ +#define GPIO_LPI2C2_SDA (GPIO_LPI2C2_SDA_1 | LPI2C_IOMUX) /* GPIO_B0_05 */ + +#define GPIO_LPI2C2_SCL_RESET (GPIO_PORT2 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_B0_04 GPIO2_IO4 */ +#define GPIO_LPI2C2_SDA_RESET (GPIO_PORT2 | GPIO_PIN5 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_B0_05 GPIO2_IO5 */ + +#define GPIO_LPI2C3_SCL (GPIO_LPI2C3_SCL_2 | LPI2C_IOMUX) /* GPIO_EMC_22 */ +#define GPIO_LPI2C3_SDA (GPIO_LPI2C3_SDA_2 | LPI2C_IOMUX) /* GPIO_EMC_21 */ + +#define GPIO_LPI2C3_SCL_RESET (GPIO_PORT4 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_22 GPIO4_IO22 */ +#define GPIO_LPI2C3_SDA_RESET (GPIO_PORT4 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_21 GPIO4_IO21 */ + +#define GPIO_LPI2C4_SCL (GPIO_LPI2C4_SCL_1 | LPI2C_IOMUX) /* GPIO_AD_B0_12 */ +#define GPIO_LPI2C4_SDA (GPIO_LPI2C4_SDA_1 | LPI2C_IOMUX) /* GPIO_AD_B0_13 */ + +#define GPIO_LPI2C4_SCL_RESET (GPIO_PORT1 | GPIO_PIN12 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B0_12 GPIO1_IO12 */ +#define GPIO_LPI2C4_SDA_RESET (GPIO_PORT1 | GPIO_PIN13 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B0_13 GPIO1_IO13 */ + +/* Ethernet Pinning */ + +#define BOARD_PHY_ADDR 18 + +#define GPIO_ENET2_MDIO /* GPIO_B0_01 */ (GPIO_ENET2_MDIO_2 | IOMUX_ENET_MDIO_DEFAULT) +#define GPIO_ENET2_MDC /* GPIO_B0_00 */ (GPIO_ENET2_MDC_2 | IOMUX_ENET_MDC_DEFAULT) +#define GPIO_ENET2_RX_EN /* GPIO_B1_03 */ (GPIO_ENET2_RX_EN_2 | IOMUX_ENET_EN_DEFAULT) /* AKA CRS_DV */ +#define GPIO_ENET2_RX_ER /* GPIO_B1_00 */ (GPIO_ENET2_RX_ER_2 | IOMUX_SLEW_FAST | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MAX | IOMUX_PULL_DOWN_100K) + +#define GPIO_ENET2_TX_EN /* GPIO_B0_14 */ (GPIO_ENET2_TX_EN_2 | IOMUX_ENET_EN_DEFAULT) +#define GPIO_ENET2_TX_CLK /* GPIO_B0_15 */ (GPIO_ENET2_REF_CLK2_2 | IOMUX_ENET_TX_CLK_DEFAULT) +#define GPIO_ENET2_RX_DATA00 /* GPIO_B1_01 */ (GPIO_ENET2_RDATA0_2 | IOMUX_ENET_DATA_DEFAULT) +#define GPIO_ENET2_RX_DATA01 /* GPIO_B1_02 */ (GPIO_ENET2_RDATA1_2 | IOMUX_ENET_DATA_DEFAULT) +#define GPIO_ENET2_TX_DATA00 /* GPIO_B0_12 */ (GPIO_ENET2_TDATA0_2 | IOMUX_ENET_DATA_DEFAULT) +#define GPIO_ENET2_TX_DATA01 /* GPIO_B0_13 */ (GPIO_ENET2_TDATA1_2 | IOMUX_ENET_DATA_DEFAULT) + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +#include +#include +// add -I build/nxp_fmurt1062-v2_default/NuttX/nuttx/arch/arm/src/chip \ to NuttX Makedefs.in +#define PROBE_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE) +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 /* GPIO_B0_06 */ (GPIO_PORT2 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) +# define PROBE_2 /* GPIO_EMC_08 */ (GPIO_PORT4 | GPIO_PIN8 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) +# define PROBE_3 /* GPIO_EMC_10 */ (GPIO_PORT4 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) +# define PROBE_4 /* GPIO_AD_B0_09 */ (GPIO_PORT1 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) +# define PROBE_5 /* GPIO_EMC_33 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) +# define PROBE_6 /* GPIO_EMC_30 */ (GPIO_PORT4 | GPIO_PIN30 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) +# define PROBE_7 /* GPIO_EMC_04 */ (GPIO_PORT4 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) +# define PROBE_8 /* GPIO_EMC_01 */ (GPIO_PORT4 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | PROBE_IOMUX) + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { imxrt_config_gpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { imxrt_config_gpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { imxrt_config_gpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { imxrt_config_gpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { imxrt_config_gpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { imxrt_config_gpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { imxrt_config_gpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { imxrt_config_gpio(PROBE_8); } \ + } while(0) + +# define PROBE(n,s) do {imxrt_gpio_write(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __NUTTX_CONFIG_NXP_FMURT1062_V2_INCLUDE_BOARD_H */ diff --git a/boards/nxp/fmurt1062-v2/nuttx-config/nsh/defconfig b/boards/nxp/fmurt1062-v2/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..21f7373c6e --- /dev/null +++ b/boards/nxp/fmurt1062-v2/nuttx-config/nsh/defconfig @@ -0,0 +1,276 @@ +# +# 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_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/nxp/fmurt1062-v2/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="imxrt" +CONFIG_ARCH_CHIP_IMXRT=y +CONFIG_ARCH_CHIP_MIMXRT1062DVL6A=y +CONFIG_ARCH_INTERRUPTSTACK=750 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_ITCM=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CUSTOM_LEDS=y +CONFIG_BOARD_FORCE_ALIGNMENT=y +CONFIG_BOARD_LOOPSPERMSEC=104926 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BOOT_RUNFROMISRAM=y +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_PRODUCTID=0x001f +CONFIG_CDCACM_PRODUCTSTR="PX4 FMURT1062 v2.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1FC9 +CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_TJA1103=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=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_IMXRT_BOOTLOADER_HEAP=y +CONFIG_IMXRT_DTCM_HEAP=y +CONFIG_IMXRT_EDMA=y +CONFIG_IMXRT_EDMA_EDBG=y +CONFIG_IMXRT_EDMA_ELINK=y +CONFIG_IMXRT_EDMA_NTCD=64 +CONFIG_IMXRT_ENET2=y +CONFIG_IMXRT_ENET=y +CONFIG_IMXRT_GPIO1_0_15_IRQ=y +CONFIG_IMXRT_GPIO1_16_31_IRQ=y +CONFIG_IMXRT_GPIO2_0_15_IRQ=y +CONFIG_IMXRT_GPIO2_16_31_IRQ=y +CONFIG_IMXRT_GPIO3_0_15_IRQ=y +CONFIG_IMXRT_GPIO3_16_31_IRQ=y +CONFIG_IMXRT_GPIO4_0_15_IRQ=y +CONFIG_IMXRT_GPIO4_16_31_IRQ=y +CONFIG_IMXRT_GPIO5_0_15_IRQ=y +CONFIG_IMXRT_GPIO5_16_31_IRQ=y +CONFIG_IMXRT_GPIO6_0_15_IRQ=y +CONFIG_IMXRT_GPIO6_16_31_IRQ=y +CONFIG_IMXRT_GPIO7_0_15_IRQ=y +CONFIG_IMXRT_GPIO7_16_31_IRQ=y +CONFIG_IMXRT_GPIO8_0_15_IRQ=y +CONFIG_IMXRT_GPIO8_16_31_IRQ=y +CONFIG_IMXRT_GPIO9_0_15_IRQ=y +CONFIG_IMXRT_GPIO9_16_31_IRQ=y +CONFIG_IMXRT_GPIO_IRQ=y +CONFIG_IMXRT_ITCM=0 +CONFIG_IMXRT_LPI2C1=y +CONFIG_IMXRT_LPI2C2=y +CONFIG_IMXRT_LPI2C3=y +CONFIG_IMXRT_LPI2C4=y +CONFIG_IMXRT_LPI2C_DMA=y +CONFIG_IMXRT_LPI2C_DMA_MAXMSG=16 +CONFIG_IMXRT_LPI2C_DYNTIMEO=y +CONFIG_IMXRT_LPI2C_DYNTIMEO_STARTSTOP=10 +CONFIG_IMXRT_LPSPI1=y +CONFIG_IMXRT_LPSPI1_DMA=y +CONFIG_IMXRT_LPSPI2=y +CONFIG_IMXRT_LPSPI2_DMA=y +CONFIG_IMXRT_LPSPI3=y +CONFIG_IMXRT_LPSPI3_DMA=y +CONFIG_IMXRT_LPSPI4=y +CONFIG_IMXRT_LPSPI4_DMA=y +CONFIG_IMXRT_LPSPI_DMA=y +CONFIG_IMXRT_LPUART2=y +CONFIG_IMXRT_LPUART3=y +CONFIG_IMXRT_LPUART4=y +CONFIG_IMXRT_LPUART5=y +CONFIG_IMXRT_LPUART6=y +CONFIG_IMXRT_LPUART7=y +CONFIG_IMXRT_LPUART8=y +CONFIG_IMXRT_LPUART_INVERT=y +CONFIG_IMXRT_LPUART_SINGLEWIRE=y +CONFIG_IMXRT_PHY_POLLING=y +CONFIG_IMXRT_PHY_PROVIDES_TXC=y +CONFIG_IMXRT_RTC_MAGIC_REG=1 +CONFIG_IMXRT_SNVS_LPSRTC=y +CONFIG_IMXRT_USBDEV=y +CONFIG_IMXRT_USDHC1=y +CONFIG_IMXRT_USDHC1_INVERT_CD=y +CONFIG_IMXRT_USDHC1_WIDTH_D1_D4=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=2944 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_LPI2C1_DMA=y +CONFIG_LPI2C2_DMA=y +CONFIG_LPI2C3_DMA=y +CONFIG_LPUART2_BAUD=57600 +CONFIG_LPUART2_RXBUFSIZE=600 +CONFIG_LPUART2_RXDMA=y +CONFIG_LPUART2_TXBUFSIZE=1500 +CONFIG_LPUART2_TXDMA=y +CONFIG_LPUART3_BAUD=57600 +CONFIG_LPUART3_IFLOWCONTROL=y +CONFIG_LPUART3_OFLOWCONTROL=y +CONFIG_LPUART3_RXBUFSIZE=600 +CONFIG_LPUART3_RXDMA=y +CONFIG_LPUART3_TXBUFSIZE=3000 +CONFIG_LPUART3_TXDMA=y +CONFIG_LPUART4_BAUD=57600 +CONFIG_LPUART4_IFLOWCONTROL=y +CONFIG_LPUART4_OFLOWCONTROL=y +CONFIG_LPUART4_RXBUFSIZE=600 +CONFIG_LPUART4_RXDMA=y +CONFIG_LPUART4_TXBUFSIZE=1500 +CONFIG_LPUART4_TXDMA=y +CONFIG_LPUART5_BAUD=57600 +CONFIG_LPUART5_RXBUFSIZE=600 +CONFIG_LPUART5_RXDMA=y +CONFIG_LPUART5_TXBUFSIZE=1500 +CONFIG_LPUART5_TXDMA=y +CONFIG_LPUART6_BAUD=57600 +CONFIG_LPUART6_RXBUFSIZE=600 +CONFIG_LPUART6_RXDMA=y +CONFIG_LPUART6_TXBUFSIZE=1500 +CONFIG_LPUART6_TXDMA=y +CONFIG_LPUART7_BAUD=57600 +CONFIG_LPUART7_RXBUFSIZE=120 +CONFIG_LPUART7_RXDMA=y +CONFIG_LPUART7_SERIAL_CONSOLE=y +CONFIG_LPUART7_TXBUFSIZE=1500 +CONFIG_LPUART7_TXDMA=y +CONFIG_LPUART8_BAUD=57600 +CONFIG_LPUART8_RXBUFSIZE=600 +CONFIG_LPUART8_TXBUFSIZE=1500 +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MM_REGIONS=3 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0XC0A800FE +CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET_LOGIN=y +CONFIG_NSH_VARS=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=1048576 +CONFIG_RAM_START=0x20200000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1800 +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_SDIO_BLOCKSETUP=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_SYSTEM_CDCACM=y +CONFIG_SYSTEM_DHCPC_RENEW=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_DMA=y +CONFIG_USBDEV_DUALSPEED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/nxp/fmurt1062-v2/nuttx-config/scripts/ocram-script.ld b/boards/nxp/fmurt1062-v2/nuttx-config/scripts/ocram-script.ld new file mode 100644 index 0000000000..b42ab54b27 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/nuttx-config/scripts/ocram-script.ld @@ -0,0 +1,299 @@ +/**************************************************************************** + * + * Copyright (C) 2018, 2020, 2022 Gregory Nutt. All rights reserved. + * Authors: Ivan Ucherdzhiev + * 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. + * + ****************************************************************************/ + +/* The FMURT1062 has 8MiB of QSPI FLASH beginning at address, + * 0x0060:0000, Upto 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM + * beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this + * configuration. + * + * The default flexram setting on the iMXRT 1062 is + * 256Kib to OCRRAM, 128Kib ITCM and 128Kib DTCM. + * This can be changed by using a dcd by minipulating + * IOMUX GPR16 and GPR17. + * The configuartion we will use is 384Kib to OCRRAM, 0Kib ITCM and + * 128Kib DTCM. + * + * This is the OCRAM inker script. + * The NXP ROM bootloader will move the FLASH image to OCRAM. + * We must reserve 32K for the bootloader' OCRAM usage from the OCRAM Size + * and an additinal 8K for the ivt_s which is IVT_SIZE(8K) This 40K can be + * reused once the application is running. + * + * 0x2020:A000 to 0x202d:ffff - The application Image's vector table + * 0x2020:8000 to 0x2020:A000 - IVT + * 0x2020:0000 to 0x2020:7fff - NXP ROM bootloader. + * + * We artificially split the FLASH to allow locating sections that we do not + * want loaded inoto OCRAM. This is to save on OCRAM where the speen of the + * code does not matter. + * + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x60000000, LENGTH = 7M + flashxip (rx) : ORIGIN = 0x60700000, LENGTH = 1M + /* Vectors @ boot+ivt OCRAM2 Flex RAM Boot IVT */ + sram (rwx) : ORIGIN = 0x2020A000, LENGTH = 512K + 256K + 128K - (32K + 8K) + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 0K + dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +EXTERN(g_flash_config) +EXTERN(g_image_vector_table) +EXTERN(g_boot_data) +EXTERN(g_dcd_data) + +ENTRY(_stext) +EXTERN(board_get_manifest) + +SECTIONS +{ + /* Image Vector Table and Boot Data for booting from external flash */ + + .boot_hdr : ALIGN(4) + { + FILL(0xff) + __boot_hdr_start__ = ABSOLUTE(.) ; + KEEP(*(.boot_hdr.conf)) + . = 0x1000 ; + KEEP(*(.boot_hdr.ivt)) + . = 0x1020 ; + KEEP(*(.boot_hdr.boot_data)) + . = 0x1030 ; + KEEP(*(.boot_hdr.dcd_data)) + __boot_hdr_end__ = ABSOLUTE(.) ; + . = 0x2000 ; + } > flash + + /* Catch all the section we want not in OCRAM so that the *(.text .text.*) in flash does not */ + /* Sift and sort with arm-none-eabi-nm -C -S -n build/nxp_fmurt1062-v2_default/nxp_fmurt1062-v2_default.elf > list.txt */ + + .flashxip : ALIGN(4) + { + FILL(0xff) + /* Order matters */ + *(.text.__start) + *(.text.imxrt_ocram_initialize) + *(.slow_memory) + *(.text.romfs*) + *(.text.cromfs*) + *(.text.mpu*) + *(.text.arm_memfault*) + *(.text.arm_hardfault*) + *(.text.up_assert*) + *(.text.up_stackdump*) + *(.text.up_taskdump*) + *(.text.up_mdelay*) + *(.text.up_udelay*) + *(.text.board_on_reset*) + *(.text.board_spi_reset*) + *(.text.board_query_manifest*) + *(.text.board_reset*) + *(.text.board_get*) + *(.text.board_mcu*) + *(.text.imxrt_xbar_connect*) + *(.text.bson*) + *(.text.*print_load*) + *(.text.*px4_mft*) + *(.text.*px4_mtd*) + *(.text.syslog*) + *(.text.register_driver*) + *(.text.nx_start*) + *(.text.nx_bringup*) + *(.text.irq_unexpected_isr*) + *(.text.group*) + *(.text.*setenv*) + *(.text.*env*) + *(.text.cmd*) + *(.text.readline*) + *(.text.mkfatfs*) + *(.text.builtin*) + *(.text.basename*) + *(.text.dirname*) + *(.text.gmtime_r*) + *(.text.chdir*) + *(.text.devnull*) + *(.text.ramdisk*) + *(.text.files*) + *(.text.unregister_driver*) + *(.text.register_blockdriver*) + *(.text.bchdev_register*) + *(.text.part*) + *(.text.ftl*) + *(.text.*I2CBusIterator*) + *(.text.*SPIBusIterator*) + *(.text.*BusCLIArguments*) + *(.text.*WorkQueueManager*) + *(.text.*param_export*) + *(.text.*param_import*) + *(.text.*param_load*) + *(.text.*BusInstanceIterator*) + *(.text.*PRINT_MODULE_USAGE*) + *(.text.*px4_getopt*) + *(.text.*main*) + *(.text.*instantiate*) + *(.text.*ADC*) + *(.text.*MS5611*) + *(.text.*I2CSPIDriver*) + *(.text.*CameraCapture*) + *(.text.*i2cdetect*) + *(.text.*usage*) +/* *(.text.*Bosch*) 2% CPU .5% RAM */ + *(.text.*Tunes*) + *(.text.*printStatistics*) + *(.text.*init*) + *(.text.*test*) + *(.text.*task_spawn*) + *(.text.*custom_command*) + *(.text.*print_usage*) + *(.text.*print_status*) + *(.text.*status*) + *(.text.*CameraInterface*) + *(.text.*CameraTrigger*) + *(.text.*ModuleBase*) + *(.text.*print_message*) + *(.text._ZN4Ekf2C2Eb) + *(.text._ZN9CommanderC2Ev) + *(.text.*PreFlightCheck*) + *(.text.*calibrat*) + *(.text.*initEv) + *(.text.*probe*) + *(.text.*thread_main*); + *(.text.*listener*) + *(.text.*BlockLocalPositionEstimator*) + *(.text.nsh_*) + *(.text.lib_vscanf) + *(.text.lib_vsprintf) + *(.text.*configure_streams_to_default*) + *(.text.*_main) + *(.text.*GPSDriverAshtech*) + *(.text.*GPSDriver*) + *(.text.*Mavlink*) + *board_hw_rev_ver.c.obj (.text .text*) + *(.rodata .rodata.*) + *(.fixup) + *(.gnu.warning) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + } > flashxip + + /* Sections that will go to OCRAM */ + + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + _etext = ABSOLUTE(.); + + } > sram AT> 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*) + __exidx_end = ABSOLUTE(.); + } > flash + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + . = ALIGN(4); + _edata = ABSOLUTE(.); + } > sram AT > flash + + .ramfunc ALIGN(4): + { + _sramfuncs = ABSOLUTE(.); + *(.ramfunc .ramfunc.*) + _eramfuncs = ABSOLUTE(.); + } > sram AT > flash + + _framfuncs = LOADADDR(.ramfunc); + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/nxp/fmurt1062-v2/nuttx-config/scripts/script.ld b/boards/nxp/fmurt1062-v2/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..0c27ef92a4 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/nuttx-config/scripts/script.ld @@ -0,0 +1,163 @@ +/**************************************************************************** + * configs/nxp_fmurt1062-v2/scripts/flash.ld + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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. + * + ****************************************************************************/ + +/* The FMURT1062 has 8MiB of QSPI FLASH beginning at address, + * 0x0060:0000, Upto 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM + * beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this + * configuratin. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x60000000, LENGTH = 8M + sram (rwx) : ORIGIN = 0x20200000, LENGTH = 768K + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 128K + dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +EXTERN(g_flash_config) +EXTERN(g_image_vector_table) +EXTERN(g_boot_data) + +ENTRY(_stext) + +SECTIONS +{ + /* Image Vector Table and Boot Data for booting from external flash */ + + .boot_hdr : ALIGN(4) + { + FILL(0xff) + __boot_hdr_start__ = ABSOLUTE(.) ; + KEEP(*(.boot_hdr.conf)) + . = 0x1000 ; + KEEP(*(.boot_hdr.ivt)) + . = 0x1020 ; + KEEP(*(.boot_hdr.boot_data)) + . = 0x1030 ; + KEEP(*(.boot_hdr.dcd_data)) + __boot_hdr_end__ = ABSOLUTE(.) ; + . = 0x2000 ; + } >flash + + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + + .init_section : + { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + + .ARM.exidx : + { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .ramfunc ALIGN(4): + { + _sramfuncs = ABSOLUTE(.); + *(.ramfunc .ramfunc.*) + _eramfuncs = ABSOLUTE(.); + } > sram AT > flash + + _framfuncs = LOADADDR(.ramfunc); + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/nxp/fmurt1062-v2/src/CMakeLists.txt b/boards/nxp/fmurt1062-v2/src/CMakeLists.txt new file mode 100644 index 0000000000..a007a98bba --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/CMakeLists.txt @@ -0,0 +1,58 @@ +############################################################################ +# +# Copyright (c) 2016, 2019 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. +# +############################################################################ + +px4_add_library(drivers_board + autoleds.c + automount.c + can.c + i2c.cpp + init.c + led.c + sdhc.c + spi.cpp + timer_config.cpp + usb.c + manifest.c + mtd.cpp + imxrt_flexspi_nor_boot.c + imxrt_flexspi_nor_flash.c +) + +target_link_libraries(drivers_board + PRIVATE + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer +) diff --git a/boards/nxp/fmurt1062-v2/src/autoleds.c b/boards/nxp/fmurt1062-v2/src/autoleds.c new file mode 100644 index 0000000000..8106e9f7a8 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/autoleds.c @@ -0,0 +1,191 @@ +/**************************************************************************** + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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. + * + ****************************************************************************/ +/* + * This module shall be used during board bring up of Nuttx. + * + * The NXP FMUK66-V3 has a separate Red, Green and Blue LEDs driven by the K66 + * as follows: + * + * LED K66 + * ------ ------------------------------------------------------- + * RED FB_CS0_b/ UART2_CTS_b / ADC0_SE5b / SPI0_SCK / FTM3_CH1/ PTD1 + * GREEN FTM2_FLT0/ CMP0_IN3/ FB_AD6 / I2S0_RX_BCLK/ FTM3_CH5/ ADC1_SE5b/ PTC9 + * BLUE CMP0_IN2/ FB_AD7 / I2S0_MCLK/ FTM3_CH4/ ADC1_SE4b/ PTC8 + * + * If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board + * the NXP fmurt1062-v1. The following definitions describe how NuttX controls + * the LEDs: + * + * SYMBOL Meaning LED state + * RED GREEN BLUE + * ------------------- ----------------------- ----------------- + * LED_STARTED NuttX has been started OFF OFF OFF + * LED_HEAPALLOCATE Heap has been allocated OFF OFF ON + * LED_IRQSENABLED Interrupts enabled OFF OFF ON + * LED_STACKCREATED Idle stack created OFF ON OFF + * LED_INIRQ In an interrupt (no change) + * LED_SIGNAL In a signal handler (no change) + * LED_ASSERTION An assertion failed (no change) + * LED_PANIC The system has crashed FLASH OFF OFF + * LED_IDLE K66 is in sleep mode (Optional, not used) + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "imxrt_gpio.h" +#include "board_config.h" +#ifdef CONFIG_ARCH_LEDS +__BEGIN_DECLS +extern void led_init(void); +__END_DECLS + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +bool nuttx_owns_leds = true; +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ +void phy_set_led(int l, bool s) +{ + +} +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/nxp/fmurt1062-v2/src/automount.c b/boards/nxp/fmurt1062-v2/src/automount.c new file mode 100644 index 0000000000..f69f7fc8f5 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/automount.c @@ -0,0 +1,304 @@ +/************************************************************************************ + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#if defined(CONFIG_FS_AUTOMOUNTER_DEBUG) && !defined(CONFIG_DEBUG_FS) +# define CONFIG_DEBUG_FS 1 +#endif + +#include +#include + +#include +#include +#include + +#include "board_config.h" +#ifdef HAVE_AUTOMOUNTER + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Types + ************************************************************************************/ +/* This structure represents the changeable state of the automounter */ + +struct fmuk66_automount_state_s { + volatile automount_handler_t handler; /* Upper half handler */ + FAR void *arg; /* Handler argument */ + bool enable; /* Fake interrupt enable */ + bool pending; /* Set if there an event while disabled */ +}; + +/* This structure represents the static configuration of an automounter */ + +struct fmuk66_automount_config_s { + /* This must be first thing in structure so that we can simply cast from struct + * automount_lower_s to struct fmuk66_automount_config_s + */ + + struct automount_lower_s lower; /* Publicly visible part */ + FAR struct fmuk66_automount_state_s *state; /* Changeable state */ +}; + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg); +static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable); +static bool fmuk66_inserted(FAR const struct automount_lower_s *lower); + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +static struct fmuk66_automount_state_s g_sdhc_state; +static const struct fmuk66_automount_config_s g_sdhc_config = { + .lower = + { + .fstype = CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE, + .blockdev = CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV, + .mountpoint = CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT, + .ddelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY), + .udelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY), + .attach = fmuk66_attach, + .enable = fmuk66_enable, + .inserted = fmuk66_inserted + }, + .state = &g_sdhc_state +}; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: fmuk66_attach + * + * Description: + * Attach a new SDHC event handler + * + * Input Parameters: + * lower - An instance of the auto-mounter lower half state structure + * isr - The new event handler to be attach + * arg - Client data to be provided when the event handler is invoked. + * + * Returned Value: + * Always returns OK + * + ************************************************************************************/ + +static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg) +{ + FAR const struct fmuk66_automount_config_s *config; + FAR struct fmuk66_automount_state_s *state; + + /* Recover references to our structure */ + + config = (FAR struct fmuk66_automount_config_s *)lower; + DEBUGASSERT(config != NULL && config->state != NULL); + + state = config->state; + + /* Save the new handler info (clearing the handler first to eliminate race + * conditions). + */ + + state->handler = NULL; + state->pending = false; + state->arg = arg; + state->handler = isr; + return OK; +} + +/************************************************************************************ + * Name: fmuk66_enable + * + * Description: + * Enable card insertion/removal event detection + * + * Input Parameters: + * lower - An instance of the auto-mounter lower half state structure + * enable - True: enable event detection; False: disable + * + * Returned Value: + * None + * + ************************************************************************************/ + +static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable) +{ + FAR const struct fmuk66_automount_config_s *config; + FAR struct fmuk66_automount_state_s *state; + irqstate_t flags; + + /* Recover references to our structure */ + + config = (FAR struct fmuk66_automount_config_s *)lower; + DEBUGASSERT(config != NULL && config->state != NULL); + + state = config->state; + + /* Save the fake enable setting */ + + flags = enter_critical_section(); + state->enable = enable; + + /* Did an interrupt occur while interrupts were disabled? */ + + if (enable && state->pending) { + /* Yes.. perform the fake interrupt if the interrutp is attached */ + + if (state->handler) { + bool inserted = fmuk66_cardinserted(); + (void)state->handler(&config->lower, state->arg, inserted); + } + + state->pending = false; + } + + leave_critical_section(flags); +} + +/************************************************************************************ + * Name: fmuk66_inserted + * + * Description: + * Check if a card is inserted into the slot. + * + * Input Parameters: + * lower - An instance of the auto-mounter lower half state structure + * + * Returned Value: + * True if the card is inserted; False otherwise + * + ************************************************************************************/ + +static bool fmuk66_inserted(FAR const struct automount_lower_s *lower) +{ + return fmuk66_cardinserted(); +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: fmuk66_automount_initialize + * + * Description: + * Configure auto-mounters for each enable and so configured SDHC + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ************************************************************************************/ + +void fmuk66_automount_initialize(void) +{ + FAR void *handle; + + finfo("Initializing automounter(s)\n"); + + /* Initialize the SDHC0 auto-mounter */ + + handle = automount_initialize(&g_sdhc_config.lower); + + if (!handle) { + ferr("ERROR: Failed to initialize auto-mounter for SDHC0\n"); + } +} + +/************************************************************************************ + * Name: fmuk66_automount_event + * + * Description: + * The SDHC card detection logic has detected an insertion or removal event. It + * has already scheduled the MMC/SD block driver operations. Now we need to + * schedule the auto-mount event which will occur with a substantial delay to make + * sure that everything has settle down. + * + * Input Parameters: + * slotno - Identifies the SDHC0 slot: SDHC0_SLOTNO or SDHC1_SLOTNO. There is a + * terminology problem here: Each SDHC supports two slots, slot A and slot B. + * Only slot A is used. So this is not a really a slot, but an HSCMI peripheral + * number. + * inserted - True if the card is inserted in the slot. False otherwise. + * + * Returned Value: + * None + * + * Assumptions: + * Interrupts are disabled. + * + ************************************************************************************/ + +void fmuk66_automount_event(bool inserted) +{ + FAR const struct fmuk66_automount_config_s *config = &g_sdhc_config; + FAR struct fmuk66_automount_state_s *state = &g_sdhc_state; + + /* Is the auto-mounter interrupt attached? */ + + if (state->handler) { + /* Yes.. Have we been asked to hold off interrupts? */ + + if (!state->enable) { + /* Yes.. just remember the there is a pending interrupt. We will + * deliver the interrupt when interrupts are "re-enabled." + */ + + state->pending = true; + + } else { + /* No.. forward the event to the handler */ + + (void)state->handler(&config->lower, state->arg, inserted); + } + } +} + +#endif /* HAVE_AUTOMOUNTER */ diff --git a/boards/nxp/fmurt1062-v2/src/board_config.h b/boards/nxp/fmurt1062-v2/src/board_config.h new file mode 100644 index 0000000000..4b97429d5e --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/board_config.h @@ -0,0 +1,508 @@ +/**************************************************************************** + * + * Copyright (c) 2018-2019 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 + * + * NXP fmukrt1062-v1 internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include "imxrt_gpio.h" +#include "imxrt_iomuxc.h" +#include "hardware/imxrt_pinmux.h" + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* PX4IO connection configuration */ +// This requires serial DMA driver +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_LPUART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_LPUART6_RX +#define PX4IO_SERIAL_BASE IMXRT_LPUART6_BASE +#define PX4IO_SERIAL_VECTOR IMXRT_IRQ_LPUART6 +#define PX4IO_SERIAL_TX_DMAMAP IMXRT_DMACHAN_LPUART6_TX +#define PX4IO_SERIAL_RX_DMAMAP IMXRT_DMACHAN_LPUART6_RX +#define PX4IO_SERIAL_CLOCK_OFF imxrt_clockoff_lpuart6 +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks +#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid +#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 2d // 2 Digital Current + +/* FMURT1062 GPIOs ***********************************************************************************/ +/* LEDs */ +/* An RGB LED is connected through GPIO as shown below: + */ +#define LED_IOMUX (IOMUX_OPENDRAIN | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW) +#define GPIO_nLED_RED /* GPIO_B0_10 QTIMER4_TIMER1 GPIO2_IO10 */ (GPIO_PORT2 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX) +#define GPIO_nLED_GREEN /* GPIO_B0_11 QTIMER4_TIMER2 GPIO2_IO11 */ (GPIO_PORT2 | GPIO_PIN11 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX) +#define GPIO_nLED_BLUE /* GPIO_B1_11 QTIMER4_TIMER3 GPIO2_IO27 */ (GPIO_PORT2 | GPIO_PIN27 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_OVERLOAD_LED LED_RED +#define BOARD_ARMED_STATE_LED LED_BLUE + + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/ +#define PX4_I2C_OBDEV_SE050 0x48 + +/* + * Define the ability to shut off off the sensor signals + * by changing the signals to inputs + */ + +#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT | IOMUX_PULL_DOWN_100K | IOMUX_CMOS_INPUT)) + +/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ + +#define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SPEED_LOW | IOMUX_SLEW_FAST) +#define OUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) + + +/* SPI off + * + * SPI1, SPI2 and SPI3 are all on VDD_3V3_SENSORS1 power domain. + * As is I2C2, I2C4 onboard sensors + * SPI4 is connected to FRAM and External1 connector. + * Power domains are FMU3V3 and VDD_5V_PERIPH + */ + +#define _GPIO_LPSPI1_MISO /* GPIO_EMC_29 GPIO4_IO29 */ (GPIO_PORT4 | GPIO_PIN29 | CS_IOMUX) +#define _GPIO_LPSPI1_MOSI /* GPIO_EMC_28 GPIO4_IO28 */ (GPIO_PORT4 | GPIO_PIN28 | CS_IOMUX) +#define _GPIO_LPSPI1_SCK /* GPIO_EMC_27 GPIO4_IO27 */ (GPIO_PORT4 | GPIO_PIN27 | CS_IOMUX) + +#define GPIO_SPI1_MISO_OFF _PIN_OFF(_GPIO_LPSPI1_MISO) +#define GPIO_SPI1_MOSI_OFF _PIN_OFF(_GPIO_LPSPI1_MOSI) +#define GPIO_SPI1_SCK_OFF _PIN_OFF(_GPIO_LPSPI1_SCK) + +#define _GPIO_LPSPI2_MISO /* GPIO_EMC_03 GPIO4_IO3 */ (GPIO_PORT4 | GPIO_PIN3 | CS_IOMUX) +#define _GPIO_LPSPI2_MOSI /* GPIO_EMC_02 GPIO4_IO2 */ (GPIO_PORT4 | GPIO_PIN2 | CS_IOMUX) +#define _GPIO_LPSPI2_SCK /* GPIO_EMC_00 GPIO4_IO0 */ (GPIO_PORT4 | GPIO_PIN0 | CS_IOMUX) + +#define GPIO_SPI2_MISO_OFF _PIN_OFF(_GPIO_LPSPI2_MISO) +#define GPIO_SPI2_MOSI_OFF _PIN_OFF(_GPIO_LPSPI2_MOSI) +#define GPIO_SPI2_SCK_OFF _PIN_OFF(_GPIO_LPSPI2_SCK) + +#define _GPIO_LPSPI3_MISO /* GPIO_AD_B1_13 GPIO1_IO29 */ (GPIO_PORT1 | GPIO_PIN29 | CS_IOMUX) +#define _GPIO_LPSPI3_MOSI /* GPIO_AD_B1_14 GPIO1_IO30 */ (GPIO_PORT1 | GPIO_PIN30 | CS_IOMUX) +#define _GPIO_LPSPI3_SCK /* GPIO_AD_B1_15 GPIO1_IO31 */ (GPIO_PORT1 | GPIO_PIN31 | CS_IOMUX) + +#define GPIO_SPI3_SCK_OFF _PIN_OFF(_GPIO_LPSPI3_SCK) +#define GPIO_SPI3_MISO_OFF _PIN_OFF(_GPIO_LPSPI3_MISO) +#define GPIO_SPI3_MOSI_OFF _PIN_OFF(_GPIO_LPSPI3_MOSI) + +/* Define the SPI4 Data Ready and Control signals */ +#define DRDY_IOMUX (IOMUX_SCHMITT_TRIGGER | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ) + +#define GPIO_SPI4_DRDY1_EXTERNAL1 /* GPIO_EMC_35 GPIO3_IO21 */ (GPIO_PORT3 | GPIO_PIN21 | GPIO_INPUT | DRDY_IOMUX) +#define GPIO_SPI4_nRESET_EXTERNAL1 /* GPIO_EMC_11 GPIO4_IO11 */ (GPIO_PORT4 | GPIO_PIN11 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX) +#define GPIO_SYNC /* GPIO_EMC_05 GPIO4_IO5 */ (GPIO_PORT4 | GPIO_PIN5 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX) + +#define GPIO_DRDY_OFF_SPI4_DRDY1_EXTERNAL1 _PIN_OFF(GPIO_SPI4_DRDY1_EXTERNAL1) +#define GPIO_SPI4_nRESET_EXTERNAL1_OFF _PIN_OFF(GPIO_SPI4_nRESET_EXTERNAL1) +#define GPIO_SYNC_OFF _PIN_OFF(GPIO_SYNC) + + +#define ADC_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) + +#define ADC1_CH(n) (n) +#define ADC1_GPIO(n, p) (GPIO_PORT1 | GPIO_PIN##p | ADC_IOMUX) // + +#define PX4_ADC_GPIO \ + /* ADC1_3V3 GPIO_AD_B1_09 GPIO1 Pin 25 */ ADC1_GPIO(14, 25), \ + /* ADC1_6V6 GPIO_AD_B0_15 GPIO1 Pin 15 */ ADC1_GPIO(4, 15), \ + /* HW_REV_SENSE GPIO_AD_B1_06 GPIO1 Pin 22 */ ADC1_GPIO(11, 22), \ + /* HW_VER_SENSE GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20), \ + /* SCALED_V5 GPIO_AD_B1_05 GPIO1 Pin 21 */ ADC1_GPIO(10, 21), \ + /* SCALED_VDD_3V3_SENSORS1 GPIO_AD_B1_11 GPIO1 Pin 27 */ ADC1_GPIO(0, 27) + +/* Define Channel numbers must match above GPIO pin IN(n)*/ + +#define ADC_ADC1_3V3_CHANNEL /* GPIO_AD_B1_09 GPIO1 Pin 25 */ ADC1_CH(14) +#define ADC_ADC1_6V6_CHANNEL /* GPIO_AD_B0_15 GPIO1 Pin 15 */ ADC1_CH(4) +#define ADC_HW_REV_SENSE_CHANNEL /* GPIO_AD_B1_06 GPIO1 Pin 22 */ ADC1_CH(11) +#define ADC_HW_VER_SENSE_CHANNEL /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_CH(9) +#define ADC_SCALED_V5_CHANNEL /* GPIO_AD_B1_05 GPIO1 Pin 21 */ ADC1_CH(10) +#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* GPIO_AD_B1_11 GPIO1 Pin 27 */ ADC1_CH(0) + +#define ADC_CHANNELS \ + ((1 << ADC_ADC1_3V3_CHANNEL) | \ + (1 << ADC_ADC1_6V6_CHANNEL) | \ + (1 << ADC_HW_REV_SENSE_CHANNEL) | \ + (1 << ADC_HW_VER_SENSE_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS_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) + +/* HW Version and Revision drive signals Default to 1 to detect */ + +#define BOARD_HAS_HW_VERSIONING + +#define HW_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MAX | IOMUX_SLEW_FAST) + +#define GPIO_HW_VER_REV_DRIVE /* GPIO_AD_B0_01 GPIO1_IO01 */ (GPIO_PORT1 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | HW_IOMUX) +#define GPIO_HW_REV_SENSE /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24) +#define GPIO_HW_VER_SENSE /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20) +#define HW_INFO_INIT_PREFIX "V5X" + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define HEATER_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) +#define GPIO_HEATER_OUTPUT /* GPIO_B1_09 QTIMER2_TIMER3 GPIO2_IO25 */ (GPIO_QTIMER2_TIMER3_1 | HEATER_IOMUX) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* WAKUP is nARMED GPIO5_IO00 + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#define nARMED_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_22K | IOMUX_DRIVE_HIZ) +#define nARMED_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) + +#define GPIO_nARMED_INIT /* WAKUP GPIO5_IO00 */ (GPIO_PORT5 | GPIO_PIN0 | GPIO_INPUT | nARMED_INPUT_IOMUX) +#define GPIO_nARMED /* WAKUP GPIO5_IO00 */ (GPIO_PORT5 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | nARMED_OUTPUT_IOMUX) + +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) + +/* PWM Capture + * + * 2 PWM Capture inputs are supported + */ +#define DIRECT_PWM_CAPTURE_CHANNELS 1 +#define CAP_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) +#define PIN_FLEXPWM2_PWMB0 /* P2:7 PWM2 B0 FMU_CAP1 */ (CAP_IOMUX | GPIO_FLEXPWM2_PWMB00_2) + +/* PWM + */ + +#define DIRECT_PWM_OUTPUT_CHANNELS 8 +#define BOARD_NUM_IO_TIMERS 8 + +// Input Capture not supported on MVP + +#define BOARD_HAS_NO_CAPTURE + +/* Power supply control and monitoring GPIOs */ + +#define GENERAL_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ) +#define GENERAL_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) + +#define GPIO_nPOWER_IN_A /* GPIO_EMC_14 GPIO4_IO14 */ (GPIO_PORT4 | GPIO_PIN14 | GPIO_INPUT | GENERAL_INPUT_IOMUX) +#define GPIO_nPOWER_IN_B /* GPIO_AD_B1_10 GPIO1_IO26 */ (GPIO_PORT1 | GPIO_PIN26 | GPIO_INPUT | GENERAL_INPUT_IOMUX) +#define GPIO_nPOWER_IN_C /* GPIO_AD_B0_14 GPIO1_IO14 */ (GPIO_PORT1 | GPIO_PIN14 | GPIO_INPUT | GENERAL_INPUT_IOMUX) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ +#define BOARD_NUMBER_BRICKS 2 +#define BOARD_NUMBER_DIGITAL_BRICKS 2 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ + +#define OC_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) + +#define GPIO_VDD_5V_PERIPH_nEN /* GPIO_EMC_09 GPIO4_IO09 */ (GPIO_PORT4 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX) +#define GPIO_VDD_5V_PERIPH_nOC /* GPIO_B1_04 GPIO2_IO20 */ (GPIO_PORT2 | GPIO_PIN20 | GPIO_INPUT | OC_INPUT_IOMUX) +#define GPIO_VDD_5V_HIPOWER_nEN /* GPIO_AD_B0_10 GPIO1_IO10 */ (GPIO_PORT1 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX) +#define GPIO_VDD_5V_HIPOWER_nOC /* GPIO_EMC_06 GPIO4_IO06 */ (GPIO_PORT4 | GPIO_PIN6 | GPIO_INPUT | OC_INPUT_IOMUX) +#define GPIO_VDD_3V3_SENSORS1_EN /* GPIO_EMC_41 GPIO3_IO27 */ (GPIO_PORT3 | GPIO_PIN27 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* GPIO_AD_B0_00 GPIO1_IO00 */ (GPIO_PORT1 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) +#define GPIO_VDD_3V3_SD_CARD_EN /* GPIO_EMC_13 GPIO4_IO13 */ (GPIO_PORT4 | GPIO_PIN13 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO |GENERAL_OUTPUT_IOMUX) + + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PMIC_ON_REQ GPIO5_IO01 */ (GPIO_PORT5 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) +//GPIO_INPUT | IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) +#define GPIO_ENET2_RX_DATA01_CONFIG4 /* GPIO_B1_02 GPIO2_IO18 (RMII-Rev) Low */ (GPIO_PORT2 | GPIO_PIN18 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) +#define GPIO_ENET2_RX_DATA00_CONFIG5 /* GPIO_B1_01 GPIO2_IO17 SLAVE:Auto Open */ (GPIO_PORT2 | GPIO_PIN17 | GPIO_INPUT | IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) +#define GPIO_ENET2_RX_EN_CONFIG6 /* GPIO_B1_03 GPIO2_IO19 SLAVE:POl Corr Low */ (GPIO_PORT2 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PMIC_STBY_REQ GPIO5_IO02 */ (GPIO_PORT5 | GPIO_PIN2 | GPIO_INPUT | GENERAL_INPUT_IOMUX) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS1_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS1_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true)) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 2 /* GPT 2 */ +#define TONE_ALARM_CHANNEL 3 /* GPIO_AD_B1_07 GPT2_COMPARE3 */ + +#define GPIO_BUZZER_1 /* GPIO_AD_B1_07 GPIO1_IO23 */ (GPIO_PORT1 | GPIO_PIN23 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM (GPIO_GPT2_COMPARE3_2 | GENERAL_OUTPUT_IOMUX) + +/* USB OTG FS + * + * VBUS_VALID is detected in USB_ANALOG_USB1_VBUS_DETECT_STAT + */ + +/* High-resolution timer */ +#define HRT_TIMER 1 /* use GPT1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */ + +#define HRT_PPM_CHANNEL /* GPIO_B1_06 GPT1_CAPTURE2 */ 2 /* use capture/compare channel 2 */ +#define GPIO_PPM_IN /* GPIO_B1_06 GPT1_CAPTURE2 */ (GPIO_GPT1_CAPTURE2_2 | GENERAL_INPUT_IOMUX) + +/* RC Serial port (When No IO) */ + +#define RC_SERIAL_PORT "/dev/ttyS5" +#define RC_SERIAL_SINGLEWIRE + +/* PWM input driver. Use FMU AUX5 pins attached to GPIO_EMC_33 GPIO3_IO19 FLEXPWM3_PWMA2 */ + +#define PWMIN_TIMER /* FLEXPWM3_PWMA2 */ 3 +#define PWMIN_TIMER_CHANNEL /* FLEXPWM3_PWMA2 */ 2 +#define GPIO_PWM_IN /* GPIO_EMC_33 GPIO3_IO19 */ (GPIO_FLEXPWM3_PWMA02_1 | GENERAL_INPUT_IOMUX) + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define SAFETY_INIT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) +#define SAFETY_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW) +#define SAFETY_SW_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_22K | IOMUX_DRIVE_HIZ) + +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* GPIO_B1_08 GPIO2_IO24 */ (GPIO_PORT2 | GPIO_PIN24 | GPIO_INPUT | SAFETY_INIT_IOMUX) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* GPIO_B1_08 GPIO2_IO24 */ (GPIO_PORT2 | GPIO_PIN24 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | SAFETY_IOMUX) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT +#define GPIO_SAFETY_SWITCH_IN /* GPIO_AD_B1_12 GPIO1_IO28 */ (GPIO_PORT1 | GPIO_PIN28 | GPIO_INPUT | SAFETY_SW_IOMUX) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * FMUv5 has a separate RC_IN + * + * GPIO PPM_IN on GPIO_B1_06 GPIO2 Pin 23 GPT1_CAPTURE2 + * SPEKTRUM_RX (it's TX or RX in Bind) on TX UART6 GPIO_EMC_25 GPIO4 Pin 25 + * Inversion is possible in the UART and can drive GPIO PPM_IN as an output + */ + +#define GPIO_PPM_IN_AS_OUT /* GPIO_B1_06 GPIO2_IO23 GPT1_CAPTURE2 GPT1_CAPTURE2 */ (GPIO_PORT2 | GPIO_PIN23 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX) +#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)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ + +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) +#define BOARD_ADC_USB_CONNECTED (board_read_VBUS_state() == 0) + +/* FMUv5 never powers odd the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#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_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + GPIO_nARMED_INIT, \ + GPIO_ETH_POWER_EN, \ + GPIO_ENET2_RX_DATA01_CONFIG4, \ + GPIO_ENET2_RX_DATA00_CONFIG5, \ + GPIO_ENET2_RX_EN_CONFIG6, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_FLEXCAN1_TX, \ + GPIO_FLEXCAN1_RX, \ + GPIO_FLEXCAN2_TX, \ + GPIO_FLEXCAN2_RX, \ + GPIO_FLEXCAN3_TX, \ + GPIO_FLEXCAN3_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS1_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \ + GPIO_SPI4_DRDY1_EXTERNAL1, \ + GPIO_SPI4_nRESET_EXTERNAL1, \ + GPIO_SYNC, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_NFC_GPIO \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 4,5 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: fmurt1062_usdhc_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int fmurt1062_usdhc_initialize(void); + +/**************************************************************************************************** + * Name: imxrt_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void imxrt_spidev_initialize(void); + +/************************************************************************************ + * Name: imxrt_spi_bus_initialize + * + * Description: + * Called to configure SPI Buses. + * + ************************************************************************************/ + +extern int imxrt1062_spi_bus_initialize(void); + +/************************************************************************************ + * Name: imxrt_usb_initialize + * + * Description: + * Called to configure USB. + * + ************************************************************************************/ + +extern int imxrt_usb_initialize(void); + +extern void imxrt_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +extern void fmurt1062_timer_initialize(void); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/nxp/fmurt1062-v2/src/can.c b/boards/nxp/fmurt1062-v2/src/can.c new file mode 100644 index 0000000000..9f0f897cbb --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/can.c @@ -0,0 +1,153 @@ +/**************************************************************************** + * + * Copyright (C) 2016, 2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include +#include "arm_internal.h" + +#include "board_config.h" + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x7; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN3)) { + enabled_interfaces &= ~(1 << 2); + } + + return enabled_interfaces; +} + +#else + + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_IMXRT_FLEXCAN1) && defined(CONFIG_IMXRT_FLEXCAN2) \ + && defined(CONFIG_IMXRT_FLEXCAN3) +# warning "CAN1 and CAN2 and CAN2 are enabled. Assuming only CAN1." +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + + /* Call imxrt_caninitialize() to get an instance of the CAN interface */ + + can = imxrt_can_initialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/boards/nxp/fmurt1062-v2/src/i2c.cpp b/boards/nxp/fmurt1062-v2/src/i2c.cpp new file mode 100644 index 0000000000..8a557078e0 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/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), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.c b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.c new file mode 100644 index 0000000000..f69b385f2e --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.c @@ -0,0 +1,64 @@ +/**************************************************************************** + * config/imxrt1060-evk/src/imxrt_flexspi_nor_boot.c + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: Ivan Ucherdzhiev + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "imxrt_flexspi_nor_boot.h" + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +__attribute__((section(".boot_hdr.ivt"))) +const struct ivt_s g_image_vector_table = { + IVT_HEADER, /* IVT Header */ + IMAGE_ENTRY_ADDRESS, /* Image Entry Function */ + IVT_RSVD, /* Reserved = 0 */ + (uint32_t)DCD_ADDRESS, /* Address where DCD information is stored */ + (uint32_t)BOOT_DATA_ADDRESS, /* Address where BOOT Data Structure is stored */ + (uint32_t)IMAG_VECTOR_TABLE, /* Pointer to IVT Self (absolute address */ + (uint32_t)CSF_ADDRESS, /* Address where CSF file is stored */ + IVT_RSVD /* Reserved = 0 */ +}; + +__attribute__((section(".boot_hdr.boot_data"))) +const struct boot_data_s g_boot_data = { + IMAGE_DEST, /* boot start location */ + (IMAGE_DEST_END - IMAGE_DEST), /* size */ + PLUGIN_FLAG, /* Plugin flag */ + 0xffffffff /* empty - extra data word */ +}; diff --git a/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.h b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.h new file mode 100644 index 0000000000..db6df9bfa6 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_boot.h @@ -0,0 +1,175 @@ +/**************************************************************************** + * boards/arm/imxrt/imxrt1060-evk/src/imxrt_flexspi_nor_boot.h + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Authors: Ivan Ucherdzhiev + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H +#define __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* IVT Data */ + +#define IVT_MAJOR_VERSION 0x4 +#define IVT_MAJOR_VERSION_SHIFT 0x4 +#define IVT_MAJOR_VERSION_MASK 0xf +#define IVT_MINOR_VERSION 0x1 +#define IVT_MINOR_VERSION_SHIFT 0x0 +#define IVT_MINOR_VERSION_MASK 0xf + +#define IVT_VERSION(major, minor) \ + ((((major) & IVT_MAJOR_VERSION_MASK) << IVT_MAJOR_VERSION_SHIFT) | \ + (((minor) & IVT_MINOR_VERSION_MASK) << IVT_MINOR_VERSION_SHIFT)) + +#define IVT_TAG_HEADER (0xd1) /* Image Vector Table */ +#define IVT_SIZE 0x2000 +#define IVT_PAR IVT_VERSION(IVT_MAJOR_VERSION, IVT_MINOR_VERSION) + +#define IVT_HEADER (IVT_TAG_HEADER | (IVT_SIZE << 8) | (IVT_PAR << 24)) +#define IVT_RSVD (uint32_t)(0x00000000) + +/* DCD Data */ + +#define DCD_TAG_HEADER (0xd2) +#define DCD_TAG_HEADER_SHIFT (24) +#define DCD_VERSION (0x40) +#define DCD_ARRAY_SIZE 1 + +#define FLASH_BASE 0x60000000 +#define FLASH_END 0x7f7fffff + +/* This needs to take into account the memory configuration at boot bootloader */ + +#define ROM_BOOTLOADER_OCRAM_RES 0x8000 +#define OCRAM_BASE (0x20200000 + ROM_BOOTLOADER_OCRAM_RES) +#define OCRAM_END (OCRAM_BASE + (512 * 1024) + (256 * 1024) - ROM_BOOTLOADER_OCRAM_RES) + + +#define SCLK 1 +#if defined(CONFIG_BOOT_RUNFROMFLASH) +# define IMAGE_DEST FLASH_BASE +# define IMAGE_DEST_END FLASH_END +# define IMAGE_DEST_OFFSET 0 +#else +# define IMAGE_DEST OCRAM_BASE +# define IMAGE_DEST_END OCRAM_END +# define IMAGE_DEST_OFFSET IVT_SIZE +#endif + +#define LOCATE_IN_DEST(x) (((uint32_t)(x)) - FLASH_BASE + IMAGE_DEST) +#define LOCATE_IN_SRC(x) (((uint32_t)(x)) - IMAGE_DEST + FLASH_BASE) + +#define DCD_ADDRESS 0 +#define BOOT_DATA_ADDRESS LOCATE_IN_DEST(&g_boot_data) +#define CSF_ADDRESS 0 +#define PLUGIN_FLAG (uint32_t)0 + +/* Located in Destination Memory */ + +#define IMAGE_ENTRY_ADDRESS ((uint32_t)&_vectors) +#define IMAG_VECTOR_TABLE LOCATE_IN_DEST(&g_image_vector_table) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* IVT Data */ + +struct ivt_s { + /* Header with tag #HAB_TAG_IVT, length and HAB version fields + * (see data) + */ + + uint32_t hdr; + + /* Absolute address of the first instruction to execute from the + * image + */ + + uint32_t entry; + + /* Reserved in this version of HAB: should be NULL. */ + + uint32_t reserved1; + + /* Absolute address of the image DCD: may be NULL. */ + + uint32_t dcd; + + /* Absolute address of the Boot Data: may be NULL, but not interpreted + * any further by HAB + */ + + uint32_t boot_data; + + /* Absolute address of the IVT. */ + + uint32_t self; + + /* Absolute address of the image CSF. */ + + uint32_t csf; + + /* Reserved in this version of HAB: should be zero. */ + + uint32_t reserved2; +}; + +/* Boot Data */ + +struct boot_data_s { + uint32_t start; /* boot start location */ + uint32_t size; /* size */ + uint32_t plugin; /* plugin flag - 1 if downloaded application is plugin */ + uint32_t placeholder; /* placehoder to make even 0x10 size */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +extern const struct boot_data_s g_boot_data; +extern const uint8_t g_dcd_data[]; +extern const uint32_t _vectors[]; + + +#endif /* __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H */ diff --git a/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.c b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.c new file mode 100644 index 0000000000..b783145fb3 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.c @@ -0,0 +1,198 @@ +/**************************************************************************** + * config/imxrt1060-evk/src/imxrt_flexspi_nor_flash.c + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Authors: Ivan Ucherdzhiev + * 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. + * + ****************************************************************************/ + +/******************************************************************************* + * Included Files + ******************************************************************************/ + + +#include "imxrt_flexspi_nor_flash.h" + +/******************************************************************************* + * Public Data + ******************************************************************************/ + +#if defined (CONFIG_NXP_FMURT1062_V3_HYPER_FLASH) +__attribute__((section(".boot_hdr.conf"))) +const struct flexspi_nor_config_s g_flash_config = { + .mem_config = + { + .tag = FLEXSPI_CFG_BLK_TAG, + .version = FLEXSPI_CFG_BLK_VERSION, + .read_sample_clksrc = FLASH_READ_SAMPLE_CLK_EXTERNALINPUT_FROM_DQSPAD, + .cs_hold_time = 3u, + .cs_setup_time = 3u, + .column_address_width = 3u, + + /* Enable DDR mode, Word addassable, Safe configuration, Differential clock */ + + .controller_misc_option = (1u << FLEXSPIMISC_OFFSET_DDR_MODE_EN) | + (1u << FLEXSPIMISC_OFFSET_WORD_ADDRESSABLE_EN) | + (1u << FLEXSPIMISC_OFFSET_SAFECONFIG_FREQ_EN) | + (1u << FLEXSPIMISC_OFFSET_DIFFCLKEN), + .sflash_pad_type = SERIAL_FLASH_8PADS, + .serial_clk_freq = FLEXSPI_SERIAL_CLKFREQ_133MHz, + .sflash_a1size = 64u * 1024u * 1024u, + .data_valid_time = {16u, 16u}, + .lookup_table = + { + /* Read LUTs */ + + FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0xA0, RADDR_DDR, FLEXSPI_8PAD, 0x18), + FLEXSPI_LUT_SEQ(CADDR_DDR, FLEXSPI_8PAD, 0x10, DUMMY_DDR, FLEXSPI_8PAD, 0x06), + FLEXSPI_LUT_SEQ(READ_DDR, FLEXSPI_8PAD, 0x04, STOP, FLEXSPI_1PAD, 0x0), + }, + }, + .page_size = 512u, + .sector_size = 256u * 1024u, + .blocksize = 256u * 1024u, + .is_uniform_blocksize = 1, +}; + +#elif defined (CONFIG_NXP_FMURT1062_V3_QSPI_FLASH) +__attribute__((section(".boot_hdr.conf"))) +const struct flexspi_nor_config_s g_flash_config = { + .mem_config = + { + .tag = FLEXSPI_CFG_BLK_TAG, + .version = FLEXSPI_CFG_BLK_VERSION, + .read_sample_clksrc = FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_SCKPAD, + .cs_hold_time = 3u, + .cs_setup_time = 3u, + .column_address_width = 0u, + .device_type = FLEXSPI_DEVICE_TYPE_SERIAL_NOR, + .sflash_pad_type = SERIAL_FLASH_4PADS, + .serial_clk_freq = FLEXSPI_SERIAL_CLKFREQ_60MHz, + .sflash_a1size = 8u * 1024u * 1024u, + .data_valid_time = {16u, 16u}, + .lookup_table = + { + /* LUTs */ + /* 0 Fast read Quad IO DTR Mode Operation in SPI Mode (normal read)*/ + + FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xED, RADDR_DDR, FLEXSPI_4PAD, 0x18), + FLEXSPI_LUT_SEQ(DUMMY_DDR, FLEXSPI_4PAD, 0x0C, READ_DDR, FLEXSPI_4PAD, 0x08), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + + /* 1 Read Status */ + + FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x05, READ_SDR, FLEXSPI_1PAD, 0x1), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + + /* 2 */ + + 0x00000000, + 0x00000000, + 0x00000000, + 0x00000000, + + /* 3 */ + + FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x06, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + + /* 4 */ + + 0x00000000, + 0x00000000, + 0x00000000, + 0x00000000, + + /* 5 Erase Sector */ + + FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xD7, RADDR_SDR, FLEXSPI_1PAD, 0x18), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + + /* 6 */ + + 0x00000000, + 0x00000000, + 0x00000000, + 0x00000000, + + /* 7 */ + + 0x00000000, + 0x00000000, + 0x00000000, + 0x00000000, + + /* 8 */ + + 0x00000000, + 0x00000000, + 0x00000000, + 0x00000000, + + /* 9 Page Program */ + + FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x02, RADDR_SDR, FLEXSPI_1PAD, 0x18), + FLEXSPI_LUT_SEQ(WRITE_SDR, FLEXSPI_1PAD, 0x8, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + + /* 10 */ + + 0x00000000, + 0x00000000, + 0x00000000, + 0x00000000, + + /* 11 Chip Erase */ + + FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xC7, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0), + + }, + }, + + .page_size = 256u, + .sector_size = 4u * 1024u, + .blocksize = 32u * 1024u, + .is_uniform_blocksize = false, +}; +#else +# error Boot Flash type not chosen! +#endif diff --git a/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.h b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.h new file mode 100644 index 0000000000..b99c135ea3 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/imxrt_flexspi_nor_flash.h @@ -0,0 +1,349 @@ +/**************************************************************************** + * config/imxrt1060-evk/src/imxrt_flexspi_nor_flash.h + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Authors: Ivan Ucherdzhiev + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H +#define __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* FLEXSPI memory config block related defintions */ + +#define FLEXSPI_CFG_BLK_TAG (0x42464346ul) +#define FLEXSPI_CFG_BLK_VERSION (0x56010400ul) +#define FLEXSPI_CFG_BLK_SIZE (512) + +/* FLEXSPI Feature related definitions */ + +#define FLEXSPI_FEATURE_HAS_PARALLEL_MODE 1 + +/* Lookup table related defintions */ + +#define CMD_INDEX_READ 0 +#define CMD_INDEX_READSTATUS 1 +#define CMD_INDEX_WRITEENABLE 2 +#define CMD_INDEX_WRITE 4 + +#define CMD_LUT_SEQ_IDX_READ 0 +#define CMD_LUT_SEQ_IDX_READSTATUS 1 +#define CMD_LUT_SEQ_IDX_WRITEENABLE 3 +#define CMD_LUT_SEQ_IDX_WRITE 9 + +#define CMD_SDR 0x01 +#define CMD_DDR 0x21 +#define RADDR_SDR 0x02 +#define RADDR_DDR 0x22 +#define CADDR_SDR 0x03 +#define CADDR_DDR 0x23 +#define MODE1_SDR 0x04 +#define MODE1_DDR 0x24 +#define MODE2_SDR 0x05 +#define MODE2_DDR 0x25 +#define MODE4_SDR 0x06 +#define MODE4_DDR 0x26 +#define MODE8_SDR 0x07 +#define MODE8_DDR 0x27 +#define WRITE_SDR 0x08 +#define WRITE_DDR 0x28 +#define READ_SDR 0x09 +#define READ_DDR 0x29 +#define LEARN_SDR 0x0a +#define LEARN_DDR 0x2a +#define DATSZ_SDR 0x0b +#define DATSZ_DDR 0x2b +#define DUMMY_SDR 0x0c +#define DUMMY_DDR 0x2c +#define DUMMY_RWDS_SDR 0x0d +#define DUMMY_RWDS_DDR 0x2d +#define JMP_ON_CS 0x1f +#define STOP 0 + +#define FLEXSPI_1PAD 0 +#define FLEXSPI_2PAD 1 +#define FLEXSPI_4PAD 2 +#define FLEXSPI_8PAD 3 + +#define FLEXSPI_LUT_OPERAND0_MASK (0xffu) +#define FLEXSPI_LUT_OPERAND0_SHIFT (0U) +#define FLEXSPI_LUT_OPERAND0(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_OPERAND0_SHIFT)) & \ + FLEXSPI_LUT_OPERAND0_MASK) +#define FLEXSPI_LUT_NUM_PADS0_MASK (0x300u) +#define FLEXSPI_LUT_NUM_PADS0_SHIFT (8u) +#define FLEXSPI_LUT_NUM_PADS0(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS0_SHIFT)) & \ + FLEXSPI_LUT_NUM_PADS0_MASK) +#define FLEXSPI_LUT_OPCODE0_MASK (0xfc00u) +#define FLEXSPI_LUT_OPCODE0_SHIFT (10u) +#define FLEXSPI_LUT_OPCODE0(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_OPCODE0_SHIFT)) & \ + FLEXSPI_LUT_OPCODE0_MASK) +#define FLEXSPI_LUT_OPERAND1_MASK (0xff0000u) +#define FLEXSPI_LUT_OPERAND1_SHIFT (16U) +#define FLEXSPI_LUT_OPERAND1(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_OPERAND1_SHIFT)) & \ + FLEXSPI_LUT_OPERAND1_MASK) +#define FLEXSPI_LUT_NUM_PADS1_MASK (0x3000000u) +#define FLEXSPI_LUT_NUM_PADS1_SHIFT (24u) +#define FLEXSPI_LUT_NUM_PADS1(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS1_SHIFT)) & \ + FLEXSPI_LUT_NUM_PADS1_MASK) +#define FLEXSPI_LUT_OPCODE1_MASK (0xfc000000u) +#define FLEXSPI_LUT_OPCODE1_SHIFT (26u) +#define FLEXSPI_LUT_OPCODE1(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE1_SHIFT)) & \ + FLEXSPI_LUT_OPCODE1_MASK) + +#define FLEXSPI_LUT_SEQ(cmd0, pad0, op0, cmd1, pad1, op1) \ + (FLEXSPI_LUT_OPERAND0(op0) | FLEXSPI_LUT_NUM_PADS0(pad0) | \ + FLEXSPI_LUT_OPCODE0(cmd0) | FLEXSPI_LUT_OPERAND1(op1) | \ + FLEXSPI_LUT_NUM_PADS1(pad1) | FLEXSPI_LUT_OPCODE1(cmd1)) + +/* */ + +#define NOR_CMD_INDEX_READ CMD_INDEX_READ +#define NOR_CMD_INDEX_READSTATUS CMD_INDEX_READSTATUS +#define NOR_CMD_INDEX_WRITEENABLE CMD_INDEX_WRITEENABLE +#define NOR_CMD_INDEX_ERASESECTOR 3 +#define NOR_CMD_INDEX_PAGEPROGRAM CMD_INDEX_WRITE +#define NOR_CMD_INDEX_CHIPERASE 5 +#define NOR_CMD_INDEX_DUMMY 6 +#define NOR_CMD_INDEX_ERASEBLOCK 7 + +/* READ LUT sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READ CMD_LUT_SEQ_IDX_READ + +/* Read Status LUT sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READSTATUS CMD_LUT_SEQ_IDX_READSTATUS + +/* 2 Read status DPI/QPI/OPI sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READSTATUS_XPI 2 + +/* 3 Write Enable sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE CMD_LUT_SEQ_IDX_WRITEENABLE + +/* 4 Write Enable DPI/QPI/OPI sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE_XPI 4 + +/* 5 Erase Sector sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_ERASESECTOR 5 + +/* 8 Erase Block sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_ERASEBLOCK 8 + +/* 9 Program sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_PAGEPROGRAM CMD_LUT_SEQ_IDX_WRITE + +/* 11 Chip Erase sequence in lookupTable id stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_CHIPERASE 11 + +/* 13 Read SFDP sequence in lookupTable id stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READ_SFDP 13 + +/* 14 Restore 0-4-4/0-8-8 mode sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_RESTORE_NOCMD 14 + +/* 15 Exit 0-4-4/0-8-8 mode sequence id in lookupTable stored in config blobk */ + +#define NOR_CMD_LUT_SEQ_IDX_EXIT_NOCMD 15 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Definitions for FlexSPI Serial Clock Frequency */ + +enum flexspi_serial_clkfreq_e { + FLEXSPI_SERIAL_CLKFREQ_30MHz = 1, + FLEXSPI_SERIAL_CLKFREQ_50MHz = 2, + FLEXSPI_SERIAL_CLKFREQ_60MHz = 3, + FLEXSPI_SERIAL_CLKFREQ_75MHz = 4, + FLEXSPI_SERIAL_CLKFREQ_80MHz = 5, + FLEXSPI_SERIAL_CLKFREQ_100MHz = 6, + FLEXSPI_SERIAL_CLKFREQ_133MHz = 7, + FLEXSPI_SERIAL_CLKFREQ_166MHz = 8, + FLEXSPI_SERIAL_CLKFREQ_200MHz = 9, +}; + +/* FlexSPI clock configuration type*/ + +enum flexspi_serial_clockmode_e { + FLEXSPI_CLKMODE_SDR, + FLEXSPI_CLKMODE_DDR, +}; + +/* FlexSPI Read Sample Clock Source definition */ + +enum flash_read_sample_clk_e { + FLASH_READ_SAMPLE_CLK_LOOPBACK_INTERNELLY = 0, + FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_DQSPAD = 1, + FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_SCKPAD = 2, + FLASH_READ_SAMPLE_CLK_EXTERNALINPUT_FROM_DQSPAD = 3, +}; + +/* Misc feature bit definitions */ + +enum flash_misc_feature_e { + FLEXSPIMISC_OFFSET_DIFFCLKEN = 0, /* Bit for Differential clock enable */ + FLEXSPIMISC_OFFSET_CK2EN = 1, /* Bit for CK2 enable */ + FLEXSPIMISC_OFFSET_PARALLELEN = 2, /* Bit for Parallel mode enable */ + FLEXSPIMISC_OFFSET_WORD_ADDRESSABLE_EN = 3, /* Bit for Word Addressable enable */ + FLEXSPIMISC_OFFSET_SAFECONFIG_FREQ_EN = 4, /* Bit for Safe Configuration Frequency enable */ + FLEXSPIMISC_OFFSET_PAD_SETTING_OVERRIDE_EN = 5, /* Bit for Pad setting override enable */ + FLEXSPIMISC_OFFSET_DDR_MODE_EN = 6, /* Bit for DDR clock confiuration indication. */ +}; + +/* Flash Type Definition */ + +enum flash_flash_type_e { + FLEXSPI_DEVICE_TYPE_SERIAL_NOR = 1, /* Flash devices are Serial NOR */ + FLEXSPI_DEVICE_TYPE_SERIAL_NAND = 2, /* Flash devices are Serial NAND */ + FLEXSPI_DEVICE_TYPE_SERIAL_RAM = 3, /* Flash devices are Serial RAM/HyperFLASH */ + FLEXSPI_DEVICE_TYPE_MCP_NOR_NAND = 0x12, /* Flash device is MCP device, A1 is Serial NOR, A2 is Serial NAND */ + FLEXSPI_DEVICE_TYPE_MCP_NOR_RAM = 0x13, /* Flash deivce is MCP device, A1 is Serial NOR, A2 is Serial RAMs */ +}; + +/* Flash Pad Definitions */ + +enum flash_flash_pad_e { + SERIAL_FLASH_1PAD = 1, + SERIAL_FLASH_2PADS = 2, + SERIAL_FLASH_4PADS = 4, + SERIAL_FLASH_8PADS = 8, +}; + +/* Flash Configuration Command Type */ + +enum flash_config_cmd_e { + DEVICE_CONFIG_CMD_TYPE_GENERIC, /* Generic command, for example: configure dummy cycles, drive strength, etc */ + DEVICE_CONFIG_CMD_TYPE_QUADENABLE, /* Quad Enable command */ + DEVICE_CONFIG_CMD_TYPE_SPI2XPI, /* Switch from SPI to DPI/QPI/OPI mode */ + DEVICE_CONFIG_CMD_TYPE_XPI2SPI, /* Switch from DPI/QPI/OPI to SPI mode */ + DEVICE_CONFIG_CMD_TYPE_SPI2NO_CMD, /* Switch to 0-4-4/0-8-8 mode */ + DEVICE_CONFIG_CMD_TYPE_RESET, /* Reset device command */ +}; + +/* FlexSPI LUT Sequence structure */ + +struct flexspi_lut_seq_s { + uint8_t seq_num; /* Sequence Number, valid number: 1-16 */ + uint8_t seq_id; /* Sequence Index, valid number: 0-15 */ + uint16_t reserved; +}; + +/* FlexSPI Memory Configuration Block */ + +struct flexspi_mem_config_s { + uint32_t tag; + uint32_t version; + uint32_t reserved0; + uint8_t read_sample_clksrc; + uint8_t cs_hold_time; + uint8_t cs_setup_time; + uint8_t column_address_width; /* [0x00f-0x00f] Column Address with, for + * HyperBus protocol, it is fixed to 3, For + * Serial NAND, need to refer to datasheet */ + uint8_t device_mode_cfg_enable; + uint8_t device_mode_type; + uint16_t wait_time_cfg_commands; + struct flexspi_lut_seq_s device_mode_seq; + uint32_t device_mode_arg; + uint8_t config_cmd_enable; + uint8_t config_mode_type[3]; + struct flexspi_lut_seq_s config_cmd_seqs[3]; + uint32_t reserved1; + uint32_t config_cmd_args[3]; + uint32_t reserved2; + uint32_t controller_misc_option; + uint8_t device_type; + uint8_t sflash_pad_type; + uint8_t serial_clk_freq; + uint8_t lut_custom_seq_enable; + uint32_t reserved3[2]; + uint32_t sflash_a1size; + uint32_t sflash_a2size; + uint32_t sflash_b1size; + uint32_t sflash_b2size; + uint32_t cspad_setting_override; + uint32_t sclkpad_setting_override; + uint32_t datapad_setting_override; + uint32_t dqspad_setting_override; + uint32_t timeout_in_ms; + uint32_t command_interval; + uint16_t data_valid_time[2]; + uint16_t busy_offset; + uint16_t busybit_polarity; + uint32_t lookup_table[64]; + struct flexspi_lut_seq_s lut_customseq[12]; + uint32_t reserved4[4]; +}; + +/* Serial NOR configuration block */ + +struct flexspi_nor_config_s { + struct flexspi_mem_config_s mem_config; /* Common memory configuration info via FlexSPI */ + uint32_t page_size; /* Page size of Serial NOR */ + uint32_t sector_size; /* Sector size of Serial NOR */ + uint8_t ipcmd_serial_clkfreq; /* Clock frequency for IP command */ + uint8_t is_uniform_blocksize; /* Sector/Block size is the same */ + uint8_t reserved0[2]; /* Reserved for future use */ + uint8_t serial_nor_type; /* Serial NOR Flash type: 0/1/2/3 */ + uint8_t need_exit_nocmdmode; /* Need to exit NoCmd mode before other IP command */ + uint8_t halfclk_for_nonreadcmd; /* Half the Serial Clock for non-read command: true/false */ + uint8_t need_restore_nocmdmode; /* Need to Restore NoCmd mode after IP commmand execution */ + uint32_t blocksize; /* Block size */ + uint32_t reserve2[11]; /* Reserved for future use */ +}; + +#endif /* __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H */ diff --git a/boards/nxp/fmurt1062-v2/src/init.c b/boards/nxp/fmurt1062-v2/src/init.c new file mode 100644 index 0000000000..e6df994f16 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/init.c @@ -0,0 +1,336 @@ +/**************************************************************************** + * + * Copyright (c) 2018-2019 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 + * + * NXP imxrt1062-v1 specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "arm_internal.h" +#include "arm_internal.h" +#include "imxrt_flexspi_nor_boot.h" +#include "imxrt_iomuxc.h" +#include +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + VDD_5V_HIPOWER_EN(false); + board_control_spi_sensors_power(false, 0xffff); + + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(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 */ + VDD_3V3_SPEKTRUM_POWER_EN(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_HIPOWER_EN(true); + 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_gpio_output(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + + +/**************************************************************************** + * Name: imxrt_ocram_initialize + * + * Description: + * Called off reset vector to reconfigure the flexRAM + * and finish the FLASH to RAM Copy. + * + ****************************************************************************/ + +__EXPORT void imxrt_ocram_initialize(void) +{ + const uint32_t *src; + uint32_t *dest; + uint32_t regval; + + /* Reallocate 128K of Flex RAM from ITCM to OCRAM + * Final Configuration is + * 128 DTCM + * + * 128 FlexRAM OCRAM (202C:0000-202D:ffff) + * 256 FlexRAM OCRAM (2028:0000-202B:ffff) + * 512 System OCRAM2 (2020:0000-2027:ffff) + * */ + + putreg32(0xaa555555, IMXRT_IOMUXC_GPR_GPR17); + regval = getreg32(IMXRT_IOMUXC_GPR_GPR16); + putreg32(regval | GPR_GPR16_FLEXRAM_BANK_CFG_SELF, IMXRT_IOMUXC_GPR_GPR16); + + for (src = (uint32_t *)(LOCATE_IN_SRC(g_boot_data.start) + g_boot_data.size), + dest = (uint32_t *)(g_boot_data.start + g_boot_data.size); + dest < (uint32_t *) &_etext;) { + *dest++ = *src++; + } +} + +/**************************************************************************** + * Name: imxrt_boardinitialize + * + * Description: + * All i.MX RT architectures must provide the following entry point. This + * entry point is called early in the initialization -- after clocking and + * memory have been configured but before caches have been enabled and + * before any devices have been initialized. + * + ****************************************************************************/ + +__EXPORT void imxrt_boardinitialize(void) +{ + + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins + * + * This includes the PHY Config Pins + */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + + imxrt_usb_initialize(); + + fmurt1062_timer_initialize(); + + /* Power up the PHY will issues a reset + * then delay by CSET2 = 0.1 uF (100Ms) so it + * can latch the pins. + */ + VDD_3V3_ETH_POWER_EN(true); + up_mdelay(110); +} + + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + + /* Power on Interfaces */ + + + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS1_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + /* TODO + * To enable SE050 driveHW_VER_REV_DRIVE low. + * Power on sequence: + * 1) Drive I2C4 lines to output low (avoid backfeeding SE050) + * 2) DoHWversioning withVDD_3V3_SENSORS1 off which will leaveHW_VER_REV_DRIVE high (SE050 disabled). + * 3) Then set HW_VER_REV_DRIVE low (SE050 enabled). + * 4) Then power onVDD_3V3_SENSORS1. + * 5) HW_VER_REV_DRIVE can be used to toggle SE050_ENAlater if needed. + */ + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + imxrt_spidev_initialize(); + + board_spi_reset(10, 0xffff); + + /* configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + + led_off(LED_RED); + led_off(LED_GREEN); + led_off(LED_BLUE); + + int ret = OK; +#if defined(CONFIG_IMXRT_USDHC) + ret = fmurt1062_usdhc_initialize(); + + if (ret != OK) { + led_on(LED_RED); + } + +#endif + + /* Configure SPI-based devices */ + + ret = imxrt1062_spi_bus_initialize(); + + if (ret != OK) { + led_on(LED_RED); + } + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + return ret; +} diff --git a/boards/nxp/fmurt1062-v2/src/led.c b/boards/nxp/fmurt1062-v2/src/led.c new file mode 100644 index 0000000000..d0912c6543 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/led.c @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * Copyright (c) 2016, 2018 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 + * + * NXP fmurt1062-v1 LED backend. + */ + +#include + +#include + +#include "chip.h" +#include +#include "board_config.h" + +#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 + + +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, // Indexed by LED_SAFETY + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + imxrt_config_gpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + imxrt_gpio_write(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + + if (g_ledmap[led] != 0) { + return imxrt_gpio_read(!g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(led, true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(led, false); +} + +__EXPORT void led_toggle(int led) +{ + + phy_set_led(led, !phy_get_led(led)); +} diff --git a/boards/nxp/fmurt1062-v2/src/manifest.c b/boards/nxp/fmurt1062-v2/src/manifest.c new file mode 100644 index 0000000000..fc596e2907 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/manifest.c @@ -0,0 +1,157 @@ +/**************************************************************************** + * + * Copyright (c) 2018, 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file manifest.c + * + * This module supplies the interface to the manifest of hardware that is + * optional and dependent on the HW REV and HW VER IDs + * + * The manifest allows the system to know whether a hardware option + * say for example the PX4IO is an no-pop option vs it is broken. + * + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "systemlib/px4_macros.h" +#include "px4_log.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +typedef struct { + uint32_t hw_ver_rev; /* the version and revision */ + const px4_hw_mft_item_t *mft; /* The first entry */ + uint32_t entries; /* the lenght of the list */ +} px4_hw_mft_list_entry_t; + +typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry; +#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1 + +static const px4_hw_mft_item_t device_unsupported = {0, 0, 0}; + +// List of components on a specific board configuration +// The index of those components is given by the enum (px4_hw_mft_item_id_t) +// declared in board_common.h +static const px4_hw_mft_item_t hw_mft_list_v0500[] = { + { + // PX4_MFT_PX4IO + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_USB + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_CAN2 + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_CAN3 + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, +}; + +static const px4_hw_mft_item_t hw_mft_list_v0540[] = { + { + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, +}; + +static px4_hw_mft_list_entry_t mft_lists[] = { + {0x0000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, + {0x0400, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)}, +}; + +/************************************************************************************ + * Name: board_query_manifest + * + * Description: + * Optional returns manifest item. + * + * Input Parameters: + * manifest_id - the ID for the manifest item to retrieve + * + * Returned Value: + * 0 - item is not in manifest => assume legacy operations + * pointer to a manifest item + * + ************************************************************************************/ + +__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id) +{ + static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized; + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + uint32_t ver_rev = board_get_hw_version() << 8; + ver_rev |= board_get_hw_revision(); + + for (unsigned i = 0; i < arraySize(mft_lists); i++) { + if (mft_lists[i].hw_ver_rev == ver_rev) { + boards_manifest = &mft_lists[i]; + break; + } + } + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + PX4_ERR("Board %4" PRIx32 " is not supported!", ver_rev); + } + } + + px4_hw_mft_item rv = &device_unsupported; + + if (boards_manifest != px4_hw_mft_list_uninitialized && + id < boards_manifest->entries) { + rv = &boards_manifest->mft[id]; + } + + return rv; +} diff --git a/boards/nxp/fmurt1062-v2/src/mtd.cpp b/boards/nxp/fmurt1062-v2/src/mtd.cpp new file mode 100644 index 0000000000..bf34673de3 --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/mtd.cpp @@ -0,0 +1,133 @@ +/**************************************************************************** + * + * Copyright (C) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi4 = { // FM25V02A on FMUM 32K 512 X 64 + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(3, 0x51) +}; +static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(4, 0x50) +}; + + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi4, + .npart = 2, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = 32 + }, + { + .type = MTD_WAYPOINTS, + .path = "/fs/mtd_waypoints", + .nblocks = 32 + + } + }, +}; + +static const px4_mtd_entry_t base_eeprom = { + .device = &i2c3, + .npart = 2, + .partd = { + { + .type = MTD_MFT_VER, + .path = "/fs/mtd_mft_ver", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 3, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 240 + }, + { + .type = MTD_MFT_REV, + .path = "/fs/mtd_mft_rev", + .nblocks = 8 + }, + { + .type = MTD_ID, + .path = "/fs/mtd_id", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 3, + .entries = { + &fmum_fram, + &base_eeprom, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mtd_mft + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/nxp/fmurt1062-v2/src/sdhc.c b/boards/nxp/fmurt1062-v2/src/sdhc.c new file mode 100644 index 0000000000..df2f92cc1c --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/sdhc.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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. + * + ****************************************************************************/ +/* A micro Secure Digital (SD) card slot is available on the board connected to + * the SD Host Controller (USDHC1) signals of the MCU. This slot will accept + * micro format SD memory cards. + * + * ------------ ------------- -------- + * SD Card Slot Board Signal IMXRT Pin + * ------------ ------------- -------- + * DAT0 USDHC1_DATA0 GPIO_SD_B0_02 + * DAT1 USDHC1_DATA1 GPIO_SD_B0_03 + * DAT2 USDHC1_DATA2 GPIO_SD_B0_04 + * CD/DAT3 USDHC1_DATA3 GPIO_SD_B0_05 + * CMD USDHC1_CMD GPIO_SD_B0_00 + * CLK USDHC1_CLK GPIO_SD_B0_01 + * CD USDHC1_CD GPIO_B1_12 + * ------------ ------------- -------- + * + * There are no Write Protect available to the IMXRT. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "imxrt_usdhc.h" + +#include "board_config.h" + +#ifdef CONFIG_IMXRT_USDHC +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/**************************************************************************** + * Private Data + ****************************************************************************/ +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fmurt1062_usdhc_initialize + * + * Description: + * Inititialize the SDHC SD card slot + * + ****************************************************************************/ + +int fmurt1062_usdhc_initialize(void) +{ + int ret; + + /* Mount the SDHC-based MMC/SD block driver */ + /* First, get an instance of the SDHC interface */ + + struct sdio_dev_s *sdhc = imxrt_usdhc_initialize(CONFIG_NSH_MMCSDSLOTNO); + + if (!sdhc) { + PX4_ERR("ERROR: Failed to initialize SDHC slot %d\n", CONFIG_NSH_MMCSDSLOTNO); + return -ENODEV; + } + + /* Now bind the SDHC interface to the MMC/SD driver */ + + ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdhc); + + if (ret != OK) { + PX4_ERR("ERROR: Failed to bind SDHC to the MMC/SD driver: %d\n", ret); + return ret; + } + + syslog(LOG_INFO, "Successfully bound SDHC to the MMC/SD driver\n"); + + return OK; +} +#endif /* CONFIG_IMXRT_USDHC */ diff --git a/boards/nxp/fmurt1062-v2/src/spi.cpp b/boards/nxp/fmurt1062-v2/src/spi.cpp new file mode 100644 index 0000000000..a3191eb23e --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/spi.cpp @@ -0,0 +1,388 @@ +/************************************************************************************ + * + * Copyright (C) 2016, 2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * 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 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include "imxrt_lpspi.h" +#include "imxrt_gpio.h" +#include "board_config.h" +#include + +#if defined(CONFIG_IMXRT_LPSPI1) || defined(CONFIG_IMXRT_LPSPI2) || \ + defined(CONFIG_IMXRT_LPSPI3) || defined(CONFIG_IMXRT_LPSPI4) + + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::LPSPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::Port3, GPIO::Pin23}, SPI::DRDY{GPIO::Port4, GPIO::Pin12}), /* GPIO_EMC_37 GPIO3_IO23, GPIO_EMC_12, GPIO4_IO12 */ + }, {GPIO::Port3, GPIO::Pin27}), // Power GPIO_EMC_41 GPIO3_IO27 + + initSPIBus(SPI::Bus::LPSPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port3, GPIO::Pin20}, SPI::DRDY{GPIO::Port3, GPIO::Pin26}), /* GPIO_EMC_34 GPIO3_IO20, GPIO_EMC_40 GPIO3_IO26 */ + }), + + initSPIBus(SPI::Bus::LPSPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin26}, SPI::DRDY{GPIO::Port4, GPIO::Pin16}), /* GPIO_B1_10 GPIO2_IO26, GPIO_EMC_16 GPIO4_IO16 */ + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin31}), /* GPIO_B1_15 GPIO2_IO31 */ + }), + + initSPIBus(SPI::Bus::LPSPI4, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::Port2, GPIO::Pin30}), /* GPIO_B1_14 GPIO2_IO30*/ + initSPIDevice(0, SPI::CS{GPIO::Port4, GPIO::Pin7}, SPI::DRDY{GPIO::Port3, GPIO::Pin21}), /* GPIO_EMC_07 GPIO4_IO07, GPIO_EMC_35 GPIO3_IO21 */ + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); + +#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT | IOMUX_PULL_DOWN_100K | IOMUX_CMOS_INPUT)) + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +/************************************************************************************ + * Name: fmurt1062_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the NXP FMUKRT1062-V1 board. + * + ************************************************************************************/ + +void imxrt_spidev_initialize(void) +{ + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + px4_arch_configgpio(px4_spi_buses[bus].devices[i].cs_gpio); + } + } + } +} + +/************************************************************************************ + * Name: imxrt_spi_bus_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the NXP FMUKRT1062-V1 board. + * + ************************************************************************************/ + +static const px4_spi_bus_t *_spi_bus1; +static const px4_spi_bus_t *_spi_bus2; +static const px4_spi_bus_t *_spi_bus3; +static const px4_spi_bus_t *_spi_bus4; + +__EXPORT int imxrt1062_spi_bus_initialize(void) +{ + for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) { + switch (px4_spi_buses[i].bus) { + case 1: _spi_bus1 = &px4_spi_buses[i]; break; + + case 2: _spi_bus2 = &px4_spi_buses[i]; break; + + case 3: _spi_bus3 = &px4_spi_buses[i]; break; + + case 4: _spi_bus4 = &px4_spi_buses[i]; break; + } + } + + /* Configure SPI-based devices */ + + struct spi_dev_s *spi_sensors = px4_spibus_initialize(1); + + if (!spi_sensors) { + PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 1); + return -ENODEV; + } + + /* Default bus 1 to 1MHz and de-assert the known chip selects. + */ + + SPI_SETFREQUENCY(spi_sensors, 1 * 1000 * 1000); + SPI_SETBITS(spi_sensors, 8); + SPI_SETMODE(spi_sensors, SPIDEV_MODE3); + + /* Get the SPI port for the Memory */ + + struct spi_dev_s *spi_memory = px4_spibus_initialize(2); + + if (!spi_memory) { + PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 2); + return -ENODEV; + } + + /* Default PX4_SPI_BUS_MEMORY to 12MHz and de-assert the known chip selects. + */ + + SPI_SETFREQUENCY(spi_memory, 12 * 1000 * 1000); + SPI_SETBITS(spi_memory, 8); + SPI_SETMODE(spi_memory, SPIDEV_MODE3); + + /* Get the SPI port for the BARO */ + + struct spi_dev_s *spi_baro = px4_spibus_initialize(3); + + if (!spi_baro) { + PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 3); + return -ENODEV; + } + + /* MS5611 has max SPI clock speed of 20MHz + */ + + SPI_SETFREQUENCY(spi_baro, 20 * 1000 * 1000); + SPI_SETBITS(spi_baro, 8); + SPI_SETMODE(spi_baro, SPIDEV_MODE3); + + /* Get the SPI port for the PX4_SPI_EXTERNAL1 */ + + struct spi_dev_s *spi_ext = px4_spibus_initialize(4); + + if (!spi_ext) { + PX4_ERR("[boot] FAILED to initialize SPI port %d\n", 4); + return -ENODEV; + } + + /* Default ext bus to 1MHz and de-assert the known chip selects. + */ + + SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000); + SPI_SETBITS(spi_ext, 8); + SPI_SETMODE(spi_ext, SPIDEV_MODE3); + + /* deselect all */ + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false); + } + } + } + + return OK; + +} + +/**************************************************************************** + * Name: imxrt_lpspi1/2/3select and imxrt_lpspi1/2/3status + * + * Description: + * The external functions, imxrt_lpspi1/2/3select and imxrt_lpspi1/2/3status must be + * provided by board-specific logic. They are implementations of the select + * and status methods of the SPI interface defined by struct spi_ops_s (see + * include/nuttx/spi/spi.h). All other methods (including imxrt_lpspibus_initialize()) + * are provided by common STM32 logic. To use this common SPI logic on your + * board: + * + * 1. Provide logic in imxrt_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide imxrt_lpspi1/2/3select() and imxrt_lpspi1/2/3status() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. Add a calls to imxrt_lpspibus_initialize() in your low level application + * initialization logic + * 4. The handle returned by imxrt_lpspibus_initialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ****************************************************************************/ + +static inline void imxrt_spixselect(const px4_spi_bus_t *bus, struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (bus->devices[i].cs_gpio == 0) { + break; + } + + if (devid == bus->devices[i].devid) { + // SPI select is active low, so write !selected to select the device + imxrt_gpio_write(bus->devices[i].cs_gpio, !selected); + } + } +} + +#if defined(CONFIG_IMXRT_LPSPI1) +__EXPORT void imxrt_lpspi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + imxrt_spixselect(_spi_bus1, dev, devid, selected); +} + +__EXPORT uint8_t imxrt_lpspi1status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} +#endif + +#if defined(CONFIG_IMXRT_LPSPI2) +__EXPORT void imxrt_lpspi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + imxrt_spixselect(_spi_bus2, dev, devid, selected); +} + +__EXPORT uint8_t imxrt_lpspi2status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} +#endif + +#if defined(CONFIG_IMXRT_LPSPI3) +__EXPORT void imxrt_lpspi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + imxrt_spixselect(_spi_bus3, dev, devid, selected); +} + +__EXPORT uint8_t imxrt_lpspi3status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} +#endif + +#if defined(CONFIG_IMXRT_LPSPI4) +__EXPORT void imxrt_lpspi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + imxrt_spixselect(_spi_bus4, dev, devid, selected); +} + +__EXPORT uint8_t imxrt_lpspi4status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} +#endif + +/************************************************************************************ + * Name: board_spi_reset + * + * Description: + * + * + ************************************************************************************/ + +__EXPORT void board_spi_reset(int ms, int bus_mask) +{ +#ifdef CONFIG_IMXRT_LPSPI1 + + /* Goal not to back feed the chips on the bus via IO lines */ + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + if (px4_spi_buses[bus].bus == 1 || px4_spi_buses[bus].bus == 3) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + imxrt_config_gpio(_PIN_OFF(px4_spi_buses[bus].devices[i].cs_gpio)); + } + + if (px4_spi_buses[bus].devices[i].drdy_gpio != 0) { + imxrt_config_gpio(_PIN_OFF(px4_spi_buses[bus].devices[i].drdy_gpio)); + } + } + } + } + + imxrt_config_gpio(GPIO_SPI1_SCK_OFF); + imxrt_config_gpio(GPIO_SPI1_MISO_OFF); + imxrt_config_gpio(GPIO_SPI1_MOSI_OFF); + + imxrt_config_gpio(GPIO_SPI3_SCK_OFF); + imxrt_config_gpio(GPIO_SPI3_MISO_OFF); + imxrt_config_gpio(GPIO_SPI3_MOSI_OFF); + + + imxrt_config_gpio(_PIN_OFF(GPIO_LPI2C3_SDA_RESET)); + imxrt_config_gpio(_PIN_OFF(GPIO_LPI2C3_SCL_RESET)); + + /* set the sensor rail off */ + imxrt_gpio_write(GPIO_VDD_3V3_SENSORS1_EN, 0); + + /* wait for the sensor rail to reach GND */ + usleep(ms * 1000); + warnx("reset done, %d ms", ms); + + /* re-enable power */ + + /* switch the sensor rail back on */ + imxrt_gpio_write(GPIO_VDD_3V3_SENSORS1_EN, 1); + + /* wait a bit before starting SPI, different times didn't influence results */ + usleep(100); + + /* reconfigure the SPI pins */ + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + if (px4_spi_buses[bus].bus == 1 || px4_spi_buses[bus].bus == 3) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + imxrt_config_gpio(px4_spi_buses[bus].devices[i].cs_gpio); + } + + if (px4_spi_buses[bus].devices[i].drdy_gpio != 0) { + imxrt_config_gpio(px4_spi_buses[bus].devices[i].drdy_gpio); + } + } + } + } + + imxrt_config_gpio(GPIO_LPSPI1_SCK); + imxrt_config_gpio(GPIO_LPSPI1_MISO); + imxrt_config_gpio(GPIO_LPSPI1_MOSI); + + imxrt_config_gpio(GPIO_LPSPI3_SCK); + imxrt_config_gpio(GPIO_LPSPI3_MISO); + imxrt_config_gpio(GPIO_LPSPI3_MOSI); + + imxrt_config_gpio(GPIO_LPI2C3_SDA); + imxrt_config_gpio(GPIO_LPI2C3_SCL); + +#endif /* CONFIG_IMXRT_LPSPI1 */ + +} + +#endif /* CONFIG_IMXRT_LPSPI1 || CONFIG_IMXRT_LPSPI2 || CONFIG_IMXRT_LPSPI3 || CONFIG_IMXRT_LPSPI4 */ diff --git a/boards/nxp/fmurt1062-v2/src/timer_config.cpp b/boards/nxp/fmurt1062-v2/src/timer_config.cpp new file mode 100644 index 0000000000..328fc3164f --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/timer_config.cpp @@ -0,0 +1,154 @@ +/**************************************************************************** + * + * Copyright (C) 2016, 2018-2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +// TODO:Stubbed out for now +#include + +#include +#include "hardware/imxrt_tmr.h" +#include "hardware/imxrt_flexpwm.h" +#include "imxrt_gpio.h" +#include "imxrt_iomuxc.h" +#include "hardware/imxrt_pinmux.h" +#include "imxrt_xbar.h" +#include "imxrt_periphclks.h" + +#include +#include + +#include "board_config.h" + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* Register accessors */ + +#define _REG(_addr) (*(volatile uint16_t *)(_addr)) + +/* QTimer3 register accessors */ + +#define REG(_reg) _REG(IMXRT_QTIMER3_BASE + IMXRT_TMR_OFFSET(IMXRT_TMR_CH0,(_reg))) + +#define rCOMP1 REG(IMXRT_TMR_COMP1_OFFSET) +#define rCOMP2 REG(IMXRT_TMR_COMP2_OFFSET) +#define rCAPT REG(IMXRT_TMR_CAPT_OFFSET) +#define rLOAD REG(IMXRT_TMR_LOAD_OFFSET) +#define rHOLD REG(IMXRT_TMR_HOLD_OFFSET) +#define rCNTR REG(IMXRT_TMR_CNTR_OFFSET) +#define rCTRL REG(IMXRT_TMR_CTRL_OFFSET) +#define rSCTRL REG(IMXRT_TMR_SCTRL_OFFSET) +#define rCMPLD1 REG(IMXRT_TMR_CMPLD1_OFFSET) +#define rCMPLD2 REG(IMXRT_TMR_CMPLD2_OFFSET) +#define rCSCTRL REG(IMXRT_TMR_CSCTRL_OFFSET) +#define rFILT REG(IMXRT_TMR_FILT_OFFSET) +#define rDMA REG(IMXRT_TMR_DMA_OFFSET) +#define rENBL REG(IMXRT_TMR_ENBL_OFFSET) + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOPWM(PWM::FlexPWM2, PWM::Submodule0), + initIOPWM(PWM::FlexPWM2, PWM::Submodule1), + initIOPWM(PWM::FlexPWM2, PWM::Submodule2), + initIOPWM(PWM::FlexPWM2, PWM::Submodule3), + initIOPWM(PWM::FlexPWM3, PWM::Submodule2), + initIOPWM(PWM::FlexPWM3, PWM::Submodule0), + initIOPWM(PWM::FlexPWM4, PWM::Submodule2), + initIOPWM(PWM::FlexPWM4, PWM::Submodule0), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06), + initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_08), + initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_10), + initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_AD_B0_09), + initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_33), + initIOTimerChannel(io_timers, {PWM::PWM3_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_30), + initIOTimerChannel(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_04), + initIOTimerChannel(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_01), +}; + +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] = { +}; + +constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { +}; + + +void fmurt1062_timer_initialize(void) +{ + /* We must configure Qtimer 3 as the IPG divide by to yield 16 Mhz + * and deliver that clock to the eFlexPWM234 via XBAR + * + * IPG = 144 Mhz + * 16Mhz = 144 / 9 + * COMP 1 = 5, COMP2 = 4 + * + * */ + + /* Enable Block Clocks for Qtimer and XBAR1 */ + + imxrt_clockall_timer3(); + imxrt_clockall_xbar1(); + + /* Disable Timer */ + + rCTRL = 0; + rCOMP1 = 5 - 1; // N - 1 + rCOMP2 = 4 - 1; + + rCAPT = 0; + rLOAD = 0; + rCNTR = 0; + + rSCTRL = TMR_SCTRL_OEN; + + rCMPLD1 = 0; + rCMPLD2 = 0; + rCSCTRL = 0; + rFILT = 0; + rDMA = 0; + + /* Count rising edges of primary source, + * Prescaler is /1 + * Count UP until compare, then re-initialize. a successful compare occurs when the counter reaches a COMP1 value. + * Toggle OFLAG output using alternating compare registers + */ + rCTRL = (TMR_CTRL_CM_MODE1 | TMR_CTRL_PCS_DIV1 | TMR_CTRL_LENGTH | TMR_CTRL_OUTMODE_TOG_ALT); + + /* QTIMER3_TIMER0 -> Flexpwm234ExtClk */ + + imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM234_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT); +} diff --git a/boards/nxp/fmurt1062-v2/src/usb.c b/boards/nxp/fmurt1062-v2/src/usb.c new file mode 100644 index 0000000000..0d3c71348d --- /dev/null +++ b/boards/nxp/fmurt1062-v2/src/usb.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * + * Copyright (C) 2016, 2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include "board_config.h" +#include "imxrt_periphclks.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int imxrt_usb_initialize(void) +{ + imxrt_clockall_usboh3(); + return 0; +} +/************************************************************************************ + * Name: imxrt_usbpullup + * + * Description: + * If USB is supported and the board supports a pullup via GPIO (for USB software + * connect and disconnect), then the board software must provide imxrt_usbpullup. + * See include/nuttx/usb/usbdev.h for additional description of this method. + * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be + * NULL. + * + ************************************************************************************/ + +__EXPORT +int imxrt_usbpullup(FAR struct usbdev_s *dev, bool enable) +{ + usbtrace(TRACE_DEVPULLUP, (uint16_t)enable); + + return OK; +} + +/************************************************************************************ + * Name: imxrt_usbsuspend + * + * Description: + * Board logic must provide the imxrt_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 imxrt_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} + +/************************************************************************************ + * Name: board_read_VBUS_state + * + * Description: + * All boards must provide a way to read the state of VBUS, this my be simple + * digital input on a GPIO. Or something more complicated like a Analong input + * or reading a bit from a USB controller register. + * + * Returns - 0 if connected. + * + ************************************************************************************/ + +int board_read_VBUS_state(void) +{ + + return (getreg32(IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT) & USB_ANALOG_USB_VBUS_DETECT_STAT_VBUS_VALID) ? 0 : 1; +} diff --git a/foo.txt b/foo.txt new file mode 100644 index 0000000000..8b13789179 --- /dev/null +++ b/foo.txt @@ -0,0 +1 @@ + diff --git a/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/px4io_serial.h b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/px4io_serial.h new file mode 100644 index 0000000000..27e5a30ec2 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/px4io_serial.h @@ -0,0 +1,169 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4io_serial.h + * + * Serial Interface definition for PX4IO + */ + +#pragma once + +#include +#include +#include + +#include + +#include +#include + +class PX4IO_serial : public device::Device +{ +public: + PX4IO_serial(); + virtual ~PX4IO_serial(); + + virtual int init() = 0; + virtual int read(unsigned offset, void *data, unsigned count = 1); + virtual int write(unsigned address, void *data, unsigned count = 1); + +protected: + /** + * Does the PX4IO_serial instance initialization. + * @param io_buffer The IO buffer that should be used for transfers. + * @return 0 on success. + */ + int init(IOPacket *io_buffer); + + /** + * Start the transaction with IO and wait for it to complete. + */ + virtual int _bus_exchange(IOPacket *_packet) = 0; + + /** + * Performance counters. + */ + perf_counter_t _pc_txns; + perf_counter_t _pc_retries; + perf_counter_t _pc_timeouts; + perf_counter_t _pc_crcerrs; + perf_counter_t _pc_protoerrs; + perf_counter_t _pc_uerrs; + perf_counter_t _pc_idle; + perf_counter_t _pc_badidle; +private: + /* + * XXX tune this value + * + * At 1.5Mbps each register takes 13.3µs, and we always transfer a full packet. + * Packet overhead is 26µs for the four-byte header. + * + * 32 registers = 451µs + * + * Maybe we can just send smaller packets (e.g. 8 regs) and loop for larger (less common) + * transfers? Could cause issues with any regs expecting to be written atomically... + */ + IOPacket *_io_buffer_ptr; + + /** bus-ownership lock */ + px4_sem_t _bus_semaphore; + + /* do not allow top copying this class */ + PX4IO_serial(PX4IO_serial &); + PX4IO_serial &operator = (const PX4IO_serial &); +}; + + +#include + + +class ArchPX4IOSerial : public PX4IO_serial +{ +public: + ArchPX4IOSerial(); + ArchPX4IOSerial(ArchPX4IOSerial &) = delete; + ArchPX4IOSerial &operator = (const ArchPX4IOSerial &) = delete; + virtual ~ArchPX4IOSerial(); + + virtual int init(); + virtual int ioctl(unsigned operation, unsigned &arg); + +protected: + /** + * Start the transaction with IO and wait for it to complete. + */ + int _bus_exchange(IOPacket *_packet); + +private: + DMACH_HANDLE _tx_dma; + DMACH_HANDLE _rx_dma; + + IOPacket *_current_packet; + + /** saved DMA status */ + static const unsigned _dma_status_done = 0x00000000; + static const unsigned _dma_status_inactive = 0x00000001; + static const unsigned _dma_status_waiting = 0x00000002; + volatile int _rx_dma_result; + + /** client-waiting lock/signal */ + px4_sem_t _completion_semaphore; + + /** + * DMA completion handler. + */ + static void _dma_callback(DMACH_HANDLE handle, void *arg, bool done, int result); + void _do_rx_dma_callback(bool done, int result); + + /** + * Serial interrupt handler. + */ + static int _interrupt(int vector, void *context, void *arg); + void _do_interrupt(); + + /** + * Cancel any DMA in progress with an error. + */ + void _abort_dma(); + + /** + * Performance counters. + */ + perf_counter_t _pc_dmaerrs; + + /** + * IO Buffer storage + */ + static uint8_t _io_buffer_storage[] px4_cache_aligned_data(); +}; diff --git a/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt index 1bb46354db..d94ea8d902 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt @@ -42,3 +42,5 @@ add_subdirectory(../imxrt/led_pwm led_pwm) add_subdirectory(../imxrt/io_pins io_pins) add_subdirectory(../imxrt/tone_alarm tone_alarm) add_subdirectory(../imxrt/version version) + +add_subdirectory(px4io_serial) diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/px4io_serial.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/px4io_serial.h new file mode 100644 index 0000000000..3252b5817f --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/px4io_serial.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include "../../../imxrt/include/px4_arch/px4io_serial.h" diff --git a/platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/CMakeLists.txt new file mode 100644 index 0000000000..df450593b1 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/CMakeLists.txt @@ -0,0 +1,36 @@ +############################################################################ +# +# Copyright (c) 2015-2019 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. +# +############################################################################ + +px4_add_library(arch_px4io_serial + px4io_serial.cpp +) diff --git a/platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/px4io_serial.cpp b/platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/px4io_serial.cpp new file mode 100644 index 0000000000..78f6ce7b4c --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/rt106x/px4io_serial/px4io_serial.cpp @@ -0,0 +1,516 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4io_serial.cpp + * + * Serial interface for PX4IO on RT1062 + */ + +#include + +#include +#include +#include "hardware/imxrt_lpuart.h" +#include "hardware/imxrt_dmamux.h" +#include "imxrt_lowputc.h" +#include "imxrt_edma.h" +#include "imxrt_periphclks.h" + + +/* serial register accessors */ +#define REG(_x) (*(volatile uint32_t *)(PX4IO_SERIAL_BASE + (_x))) +#define rBAUD REG(IMXRT_LPUART_BAUD_OFFSET) +#define rSTAT_ERR_FLAGS_MASK (LPUART_STAT_PF | LPUART_STAT_FE | LPUART_STAT_NF | LPUART_STAT_OR) +#define rSTAT REG(IMXRT_LPUART_STAT_OFFSET) +#define rCTRL REG(IMXRT_LPUART_CTRL_OFFSET) +#define rDATA REG(IMXRT_LPUART_DATA_OFFSET) + +#define DMA_BUFFER_MASK (ARMV7M_DCACHE_LINESIZE - 1) +#define DMA_ALIGN_UP(n) (((n) + DMA_BUFFER_MASK) & ~DMA_BUFFER_MASK) + +uint8_t ArchPX4IOSerial::_io_buffer_storage[DMA_ALIGN_UP(sizeof(IOPacket))]; + +ArchPX4IOSerial::ArchPX4IOSerial() : + _tx_dma(nullptr), + _rx_dma(nullptr), + _current_packet(nullptr), + _rx_dma_result(_dma_status_inactive), + _completion_semaphore(SEM_INITIALIZER(0)), + _pc_dmaerrs(perf_alloc(PC_COUNT, MODULE_NAME": DMA errors")) +{ +} + +ArchPX4IOSerial::~ArchPX4IOSerial() +{ + if (_tx_dma != nullptr) { + imxrt_dmach_stop(_tx_dma); + imxrt_dmach_free(_tx_dma); + } + + if (_rx_dma != nullptr) { + imxrt_dmach_stop(_rx_dma); + imxrt_dmach_free(_rx_dma); + } + + /* reset the UART */ + rCTRL = 0; + + /* detach our interrupt handler */ + up_disable_irq(PX4IO_SERIAL_VECTOR); + irq_detach(PX4IO_SERIAL_VECTOR); + + /* restore the GPIOs */ + px4_arch_unconfiggpio(PX4IO_SERIAL_TX_GPIO); + px4_arch_unconfiggpio(PX4IO_SERIAL_RX_GPIO); + + /* Disable clock for the USART peripheral */ + PX4IO_SERIAL_CLOCK_OFF(); + + /* and kill our semaphores */ + px4_sem_destroy(&_completion_semaphore); + + perf_free(_pc_dmaerrs); +} + +int +ArchPX4IOSerial::init() +{ + /* initialize base implementation */ + int r = PX4IO_serial::init((IOPacket *)&_io_buffer_storage[0]); + + if (r != 0) { + return r; + } + + /* allocate DMA */ + _tx_dma = imxrt_dmach_alloc(PX4IO_SERIAL_TX_DMAMAP | DMAMUX_CHCFG_ENBL, 0); + _rx_dma = imxrt_dmach_alloc(PX4IO_SERIAL_RX_DMAMAP | DMAMUX_CHCFG_ENBL, 0); + + if ((_tx_dma == nullptr) || (_rx_dma == nullptr)) { + return -1; + } + + struct uart_config_s config = { + .baud = PX4IO_SERIAL_BITRATE, + .parity = 0, /* 0=none, 1=odd, 2=even */ + .bits = 8, /* Number of bits (5-9) */ + .stopbits2 = false, /* true: Configure with 2 stop bits instead of 1 */ + .userts = false, /* True: Assert RTS when there are data to be sent */ + .invrts = false, /* True: Invert sense of RTS pin (true=active high) */ + .usects = false, /* True: Condition transmission on CTS asserted */ + .users485 = false, /* True: Assert RTS while transmission progresses */ + }; + + + int rv = imxrt_lpuart_configure(PX4IO_SERIAL_BASE, &config); + + if (rv == OK) { + /* configure pins for serial use */ + px4_arch_configgpio(PX4IO_SERIAL_TX_GPIO); + px4_arch_configgpio(PX4IO_SERIAL_RX_GPIO); + + /* attach serial interrupt handler */ + irq_attach(PX4IO_SERIAL_VECTOR, _interrupt, this); + up_enable_irq(PX4IO_SERIAL_VECTOR); + + /* Idel after Stop, , enable error and line idle interrupts */ + uint32_t regval = rCTRL; + regval &= ~(LPUART_CTRL_IDLECFG_MASK | LPUART_CTRL_ILT); + regval |= LPUART_CTRL_ILT | LPUART_CTRL_IDLECFG_1 | LPUART_CTRL_ILIE | + LPUART_CTRL_RE | LPUART_CTRL_TE; + rCTRL = regval; + + /* create semaphores */ + px4_sem_init(&_completion_semaphore, 0, 0); + + /* _completion_semaphore use case is a signal */ + + px4_sem_setprotocol(&_completion_semaphore, SEM_PRIO_NONE); + + /* XXX this could try talking to IO */ + } + + return rv; +} + +int +ArchPX4IOSerial::ioctl(unsigned operation, unsigned &arg) +{ + switch (operation) { + + case 1: /* XXX magic number - test operation */ + switch (arg) { + case 0: + syslog(LOG_INFO, "test 0\n"); + + /* kill DMA, this is a PIO test */ + imxrt_dmach_stop(_tx_dma); + imxrt_dmach_stop(_rx_dma); + + /* disable UART DMA */ + + rBAUD &= ~(LPUART_BAUD_RDMAE | LPUART_BAUD_TDMAE); + + for (;;) { + while (!(rSTAT & LPUART_STAT_TDRE)) + ; + + rDATA = 0x55; + } + + return 0; + + case 1: { + unsigned fails = 0; + + for (unsigned count = 0;; count++) { + uint16_t value = count & 0xffff; + + if (write((PX4IO_PAGE_TEST << 8) | PX4IO_P_TEST_LED, &value, 1) != 0) { + fails++; + } + + if (count >= 5000) { + syslog(LOG_INFO, "==== test 1 : %u failures ====\n", fails); + perf_print_counter(_pc_txns); + perf_print_counter(_pc_retries); + perf_print_counter(_pc_timeouts); + perf_print_counter(_pc_crcerrs); + perf_print_counter(_pc_dmaerrs); + perf_print_counter(_pc_protoerrs); + perf_print_counter(_pc_uerrs); + perf_print_counter(_pc_idle); + perf_print_counter(_pc_badidle); + count = 0; + } + } + + return 0; + } + + case 2: + syslog(LOG_INFO, "test 2\n"); + return 0; + } + + default: + break; + } + + return -1; +} + +int +ArchPX4IOSerial::_bus_exchange(IOPacket *_packet) +{ + // to be paranoid ensure all previous DMA transfers are cleared + _abort_dma(); + + _current_packet = _packet; + + /* clear data that may be in the RDR and clear overrun error: */ + while (rSTAT & LPUART_STAT_RDRF) { + (void)rDATA; + } + + rSTAT |= (rSTAT_ERR_FLAGS_MASK | LPUART_STAT_IDLE); /* clear the flags */ + + /* start RX DMA */ + perf_begin(_pc_txns); + + /* DMA setup time ~3µs */ + _rx_dma_result = _dma_status_waiting; + + struct imxrt_edma_xfrconfig_s rx_config; + rx_config.saddr = PX4IO_SERIAL_BASE + IMXRT_LPUART_DATA_OFFSET; + rx_config.daddr = reinterpret_cast(_current_packet); + rx_config.soff = 0; + rx_config.doff = 1; + rx_config.iter = sizeof(*_current_packet); + rx_config.flags = EDMA_CONFIG_LINKTYPE_LINKNONE; + rx_config.ssize = EDMA_8BIT; + rx_config.dsize = EDMA_8BIT; + rx_config.nbytes = 1; +#ifdef CONFIG_IMXRT_EDMA_ELINK + rx_config.linkch = NULL; +#endif + imxrt_dmach_xfrsetup(_rx_dma, &rx_config); + + /* Enable receive DMA for the UART */ + + rBAUD |= LPUART_BAUD_RDMAE; + + imxrt_dmach_start(_rx_dma, _dma_callback, (void *)this); + + /* Clean _current_packet, so DMA can see the data */ + up_clean_dcache((uintptr_t)_current_packet, + (uintptr_t)_current_packet + DMA_ALIGN_UP(sizeof(IOPacket))); + + /* start TX DMA - no callback if we also expect a reply */ + /* DMA setup time ~3µs */ + + struct imxrt_edma_xfrconfig_s tx_config; + tx_config.saddr = reinterpret_cast(_current_packet); + tx_config.daddr = PX4IO_SERIAL_BASE + IMXRT_LPUART_DATA_OFFSET; + tx_config.soff = 1; + tx_config.doff = 0; + tx_config.iter = sizeof(*_current_packet); + tx_config.flags = EDMA_CONFIG_LINKTYPE_LINKNONE; + tx_config.ssize = EDMA_8BIT; + tx_config.dsize = EDMA_8BIT; + tx_config.nbytes = 1; +#ifdef CONFIG_IMXRT_EDMA_ELINK + tx_config.linkch = NULL; +#endif + imxrt_dmach_xfrsetup(_tx_dma, &tx_config); + + + /* Enable transmit DMA for the UART */ + + rBAUD |= LPUART_BAUD_TDMAE; + + imxrt_dmach_start(_tx_dma, nullptr, nullptr); + + /* compute the deadline for a 10ms timeout */ + struct timespec abstime; + clock_gettime(CLOCK_REALTIME, &abstime); + abstime.tv_nsec += 10 * 1000 * 1000; + + if (abstime.tv_nsec >= 1000 * 1000 * 1000) { + abstime.tv_sec++; + abstime.tv_nsec -= 1000 * 1000 * 1000; + } + + /* wait for the transaction to complete - 64 bytes @ 1.5Mbps ~426µs */ + int ret; + + for (;;) { + ret = sem_timedwait(&_completion_semaphore, &abstime); + + if (ret == OK) { + /* check for DMA errors */ + if (_rx_dma_result != OK) { + // stream transfer error, ensure all DMA is also stopped before exiting early + _abort_dma(); + perf_count(_pc_dmaerrs); + ret = -EIO; + break; + } + + /* check packet CRC - corrupt packet errors mean IO receive CRC error */ + uint8_t crc = _current_packet->crc; + _current_packet->crc = 0; + + if ((crc != crc_packet(_current_packet)) || (PKT_CODE(*_current_packet) == PKT_CODE_CORRUPT)) { + _abort_dma(); + perf_count(_pc_crcerrs); + ret = -EIO; + break; + } + + /* successful txn (may still be reporting an error) */ + break; + } + + if (errno == ETIMEDOUT) { + /* something has broken - clear out any partial DMA state and reconfigure */ + _abort_dma(); + perf_count(_pc_timeouts); + perf_cancel(_pc_txns); /* don't count this as a transaction */ + break; + } + + /* we might? see this for EINTR */ + syslog(LOG_ERR, "unexpected ret %d/%d\n", ret, errno); + } + + /* reset DMA status */ + _rx_dma_result = _dma_status_inactive; + + /* update counters */ + perf_end(_pc_txns); + + return ret; +} + +void +ArchPX4IOSerial::_dma_callback(DMACH_HANDLE handle, void *arg, bool done, int result) +{ + if (arg != nullptr) { + ArchPX4IOSerial *ps = reinterpret_cast(arg); + + ps->_do_rx_dma_callback(done, result); + } +} + +void +ArchPX4IOSerial::_do_rx_dma_callback(bool done, int result) +{ + /* on completion of a reply, wake the waiter */ + + if (done && _rx_dma_result == _dma_status_waiting) { + + if (result != OK) { + + /* check for packet overrun - this will occur after DMA completes */ + uint32_t sr = rSTAT; + + if (sr & (LPUART_STAT_OR | LPUART_STAT_RDRF)) { + while (rSTAT & LPUART_STAT_RDRF) { + (void)rDATA; + } + + rSTAT = sr & (LPUART_STAT_OR); + result = -EIO; + } + } + + /* save RX status */ + _rx_dma_result = result; + + /* disable UART DMA */ + + rBAUD &= ~(LPUART_BAUD_RDMAE | LPUART_BAUD_TDMAE); + + /* complete now */ + px4_sem_post(&_completion_semaphore); + } +} + +int +ArchPX4IOSerial::_interrupt(int irq, void *context, void *arg) +{ + if (arg != nullptr) { + ArchPX4IOSerial *instance = reinterpret_cast(arg); + + instance->_do_interrupt(); + } + + return 0; +} + +void +ArchPX4IOSerial::_do_interrupt() +{ + uint32_t sr = rSTAT; + + while (rSTAT & LPUART_STAT_RDRF) { + (void)rDATA; /* read DATA register to clear RDRF */ + } + + rSTAT |= sr & rSTAT_ERR_FLAGS_MASK; /* clear flags */ + + if (sr & (LPUART_STAT_OR | /* overrun error - packet was too big for DMA or DMA was too slow */ + LPUART_STAT_NF | /* noise error - we have lost a byte due to noise */ + LPUART_STAT_FE)) { /* framing error - start/stop bit lost or line break */ + + /* + * If we are in the process of listening for something, these are all fatal; + * abort the DMA with an error. + */ + if (_rx_dma_result == _dma_status_waiting) { + _abort_dma(); + + perf_count(_pc_uerrs); + /* complete DMA as though in error */ + _do_rx_dma_callback(true, -EIO); + + return; + } + + /* XXX we might want to use FE / line break as an out-of-band handshake ... handle it here */ + + /* don't attempt to handle IDLE if it's set - things went bad */ + return; + } + + if (sr & LPUART_STAT_IDLE) { + + rSTAT |= LPUART_STAT_IDLE; /* clear IDLE flag */ + + /* if there is DMA reception going on, this is a short packet */ + if (_rx_dma_result == _dma_status_waiting) { + /* Invalidate _current_packet, so we get fresh data from RAM */ + up_invalidate_dcache((uintptr_t)_current_packet, + (uintptr_t)_current_packet + DMA_ALIGN_UP(sizeof(IOPacket))); + + /* verify that the received packet is complete */ + size_t length = sizeof(*_current_packet) - imxrt_dmach_getcount(_rx_dma); + + if ((length < 1) || (length < PKT_SIZE(*_current_packet))) { + perf_count(_pc_badidle); + + /* stop the receive DMA */ + imxrt_dmach_stop(_rx_dma); + + /* complete the short reception */ + _do_rx_dma_callback(true, -EIO); + return; + } + + perf_count(_pc_idle); + + /* complete the short reception */ + + _do_rx_dma_callback(true, _dma_status_done); + + /* stop the receive DMA */ + imxrt_dmach_stop(_rx_dma); + } + } +} + +void +ArchPX4IOSerial::_abort_dma() +{ + /* stop DMA */ + imxrt_dmach_stop(_tx_dma); + imxrt_dmach_stop(_rx_dma); + + /* disable UART DMA */ + + rBAUD &= ~(LPUART_BAUD_RDMAE | LPUART_BAUD_TDMAE); + + /* clear data that may be in the DATA register and clear overrun error: */ + uint32_t sr = rSTAT; + + if (sr & (LPUART_STAT_OR | LPUART_STAT_RDRF)) { + + while (rSTAT & LPUART_STAT_RDRF) { + (void)rDATA; + } + } + + rSTAT |= sr & (rSTAT_ERR_FLAGS_MASK | LPUART_STAT_IDLE); /* clear flags */ +}