From ff51389f474d147de0f3712315c5ea69fbd5095f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 25 May 2022 11:03:45 -0400 Subject: [PATCH] WIP: qiotek h743 board support --- boards/qiotek/zealoth743/bootloader.px4board | 3 + boards/qiotek/zealoth743/default.px4board | 106 +++++++ .../extras/cuav_nora_bootloader.bin | Bin 0 -> 42908 bytes boards/qiotek/zealoth743/firmware.prototype | 13 + .../qiotek/zealoth743/init/rc.board_defaults | 22 ++ .../qiotek/zealoth743/init/rc.board_sensors | 29 ++ .../nuttx-config/bootloader/defconfig | 93 ++++++ .../zealoth743/nuttx-config/include/board.h | 268 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 49 ++++ .../zealoth743/nuttx-config/nsh/defconfig | 233 +++++++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 223 +++++++++++++++ .../zealoth743/nuttx-config/scripts/script.ld | 222 +++++++++++++++ boards/qiotek/zealoth743/src/CMakeLists.txt | 66 +++++ boards/qiotek/zealoth743/src/board_config.h | 228 +++++++++++++++ .../qiotek/zealoth743/src/bootloader_main.c | 75 +++++ boards/qiotek/zealoth743/src/hw_config.h | 135 +++++++++ boards/qiotek/zealoth743/src/i2c.cpp | 39 +++ boards/qiotek/zealoth743/src/init.c | 219 ++++++++++++++ boards/qiotek/zealoth743/src/led.c | 111 ++++++++ boards/qiotek/zealoth743/src/spi.cpp | 56 ++++ boards/qiotek/zealoth743/src/timer_config.cpp | 82 ++++++ boards/qiotek/zealoth743/src/usb.c | 59 ++++ 22 files changed, 2331 insertions(+) create mode 100644 boards/qiotek/zealoth743/bootloader.px4board create mode 100644 boards/qiotek/zealoth743/default.px4board create mode 100755 boards/qiotek/zealoth743/extras/cuav_nora_bootloader.bin create mode 100644 boards/qiotek/zealoth743/firmware.prototype create mode 100644 boards/qiotek/zealoth743/init/rc.board_defaults create mode 100644 boards/qiotek/zealoth743/init/rc.board_sensors create mode 100644 boards/qiotek/zealoth743/nuttx-config/bootloader/defconfig create mode 100644 boards/qiotek/zealoth743/nuttx-config/include/board.h create mode 100644 boards/qiotek/zealoth743/nuttx-config/include/board_dma_map.h create mode 100644 boards/qiotek/zealoth743/nuttx-config/nsh/defconfig create mode 100644 boards/qiotek/zealoth743/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/qiotek/zealoth743/nuttx-config/scripts/script.ld create mode 100644 boards/qiotek/zealoth743/src/CMakeLists.txt create mode 100644 boards/qiotek/zealoth743/src/board_config.h create mode 100644 boards/qiotek/zealoth743/src/bootloader_main.c create mode 100644 boards/qiotek/zealoth743/src/hw_config.h create mode 100644 boards/qiotek/zealoth743/src/i2c.cpp create mode 100644 boards/qiotek/zealoth743/src/init.c create mode 100644 boards/qiotek/zealoth743/src/led.c create mode 100644 boards/qiotek/zealoth743/src/spi.cpp create mode 100644 boards/qiotek/zealoth743/src/timer_config.cpp create mode 100644 boards/qiotek/zealoth743/src/usb.c diff --git a/boards/qiotek/zealoth743/bootloader.px4board b/boards/qiotek/zealoth743/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/qiotek/zealoth743/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/qiotek/zealoth743/default.px4board b/boards/qiotek/zealoth743/default.px4board new file mode 100644 index 0000000000..1c7e018398 --- /dev/null +++ b/boards/qiotek/zealoth743/default.px4board @@ -0,0 +1,106 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_OSD=y +CONFIG_DRIVERS_PCA9685=y +CONFIG_DRIVERS_PCA9685_PWM_OUT=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PWM_OUT_SIM=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_RPM=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL_L1=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MIXER=y +CONFIG_SYSTEMCMDS_MOTOR_TEST=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_PWM=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y +CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/qiotek/zealoth743/extras/cuav_nora_bootloader.bin b/boards/qiotek/zealoth743/extras/cuav_nora_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..3ba1922daa31741dfedda815bc2749580054c7b4 GIT binary patch literal 42908 zcmeFZdwf*I`9D7Avb!hQklkE>%>}X-F1dl51T=!yWjCB$77Q2La7Da^(q(1}3M8Q_8_Pfi)1_Ct-vXFqBC4oJ;?)N>rU|Y4n*Z23| z?~m`kUbE+%Idf*7dFGjCp4&{Hz%DR0Q21_?z(m%&_dT@s_&(Zp0T5EcQjWs<{8*6*w zHdYpPvSggllvYAaY0f%(&atu1w34*qP4-)k5jmyrN>5^~L*}{Kp2UqQB?;25YhOHS zk!_9-mA7&dBu8&0m*66DSzl{U>2F$lR{SObWh^p--1*__eAmr4L>32$9NSOiIfD*` zPx;tCPvNz=(|+t9OeEtv2^j~JjC=2OBGCIOS4ih(q=nA)`;sMduiI?zb>}9#epbS4 zWpc+SwQ<*Ja?8kWE-cwdEe_U)4C{pl_+CF znY!=p>s$_JK}q`bol6}h$z_g`on`DblAFBDUUF(_vSgQc&r5bCOIw-26UmYu|5MP< z9c1vtbX*;>8gT& zmNl$h=2-eIE9bL@%zj^1QFaN3KG^0vddYl_!rg0Ih5JCx9d`sekSCAB^Jjg*c@ zI!BeHNO2pvUiV{F9wsNw9l!B0&p{8d(6{FrH=yhu4{x--N923oE%q?CU-pyCD_%#h zdzHE*!Npj*{A7~fYr!*%=dbFdJv|S;Y*I$nOpqrHL*DxHyNptxY%jH9k`NQ#Wb{ zjdd~1*~VxG>!S5qTh{L*=9yQQEZKMMiFMj`Vzyo1#VkvY!(DW`0srI>r5?<}`b~EB z%&XU)sJ!TB>X|&I?wUW6%bZ!3|ILlO>*2i9S&H?n$2FSBLN1mL9(@{j5*pq^)DbTlud@r+^fLq(>SD zc=es6bBvSLJ*HUSlp=B9REtu%K)z*3UOkxsKDfy~;2Z56U2K?@gHaIN&F)SZhqiXusS~%(`OENaXGP7Vxum4u{<7u()Ik9nGbG)?@s6 zwC$!a0S@q3A(dXwkxoh%FGmq!4N^jr+rqqAF7je1I5%W$)@7f$NOIUSNiKGuz6JBN zi_T=lpU_0UD|hFQl#6yGyZZcLTwSy(~ju?jKjTcTI+PFhnWFHu>#;<}&0Yxr{Gm!GRYe|+t+m}4i`pN!8Ys%Twe z(pXD6Y2DjH+@y&)KxAHF-XkrMXFk)_L1Zp=Nl$I;6V787Vr80tGsP*)bb_=iz_9=A ze$qubEj?4y;klrsy^6Fekj|!O22Xvdy!2IR*H-O6FKFet3P0V3Gy$uvfxL=j!d*V@ z@<}T0s&H3DM&nMwokHU29fLb&1ij;M#|iXKgF6jfvlSigbS)R;G!|w35=U6z9V|X-*1%X;#e;W-xGjzRbFa4g58(_8EtS2&#Jc~ImJzVI#9d$gVxMqB$EXz53k!;}P+lK5;<_$?4<6DM*F$SZiw2ibN|H9)XP!1oWZVc>iZr3Hd&ma{r+4ZEt}eN<0}SW9~kTYZcP-NZXJ$AT2;T4PG!ch6oo>#*OD? zNUM=tNTx(0lpBe#zm^CmQYoJz<3hpokjh!wo4<6KiEQK1uYV{;k@6|h8rVUE^gl$( z(K2M|@QpJ6{H}~|1Q8~o%pcP$n^av7WQJONKZ$7(;$vaz1c_pnU zzbVm~Dt(4`69)D*qd!mmkoO+w8*3$5QKyOJY;BY?MVjAyxsl2N#F*d0Os{W5ZCTfR zSNx0|GY|lbv|c)9l}%6Y<3-Gc%2@I9i+nC8>-$vV$DWuSPuH?rv^$tB(L2r{pKLKf z?wF$RV^ycpMNa+(7+3GBY)KcJ`eJNEZs@!2Um zDX;>UA4MmAFOB5!1vo zO8TorKGMgJE$B!W)iS5XO3=@b&F}b?XP!uB9s@e($L4kzO!WTtfsM@+p7hRKF*;yi zXkH(_zH(|$1-CyZT)v?{rE`x|Eb2?>97-3p_2hSSjpE0S=!n@l17(Q(sY3sE_3@(3 zqba66Uob#!Iqjvnuk=yM1lN0pwD!dlfzms8ZRu0MD0&~y)!m@I@5!5AD*0QGYW^lR zV?89sc7^O?atll28}F2M+edWdOO!+0q1cO6B1xa^yWU8t61^d|PA2nC>D^Yw%-lKB zR@(JZjJEru*u~1!Ib_mQ-`^EtyWWV}tZ$;;mkQoec;l`b`Yl_}8DCcNjg}=`Jza5L zR(O5cl7>yD$1U<A0KDrw!TpCz_7X4h&~?!w`zDi6g)Vb zE~;pcf5YT5*7(NP{nI28;A6nGs^^huE@B=n3etMJu4AD{jPa$@Bq4|GKKkgs?xi|y z#{!X+KM8%TkU8u9Gr>!;mE2Ay_dM!gtT}!BXUw#@if~6v7t5-;Ka4>Mnww2~amr8m z2E{Ms8R4%)yn_YV{l_%LS{krQ<0kfZ)N-~;-bvi$dGhLJDz zMYIroOMa6c{J;nb{QJOhWtoXF0-CsaiqYz9ZrF5xIVW=*nue`YHV> z;5MOPQ|Mbig$qzw)u71;JVgHUp?~Fm{9W#zL&TykQ5PkNOy28RA7a&I0|Kk~Lct8k z29!rr-du_L=IjS#q|<}hN_DjFX;C^SnUEqe(>dFSB9$~#$#W5jbRXtG^Of6gXlxA? z2_A~OC&F;ng}@i&dxq&ca&x`2dbo`#JaZg6jGM|NbbYBT)Hj8KS3{JiF0*s;QiX?h z5Sn5X^({)%XfesD#tJq@3I*jsou}gA>8|4x##&+yuV(8X{WH}g*F%G4C&ziY$%$TO za-#2{hfPwngN%DKKwA{Zo3E1Id~hlZ5&q0_wluApS6YCP2@_&k;;gAFSD83&B-}^%nn*QLE%NK zhZ#ff>wyI#PgXeCaJ~V)Um0YKU*2dZzo}LVuV7}k5!x#H;J(oZV!XF}wa2{XIlJ1& z1rix+vw)Fbsqmdfahw$JbMj+KWKA=Q`7Qb;?#WuZ7H;^yHXmEe$+s#u=L(w@Gmc7xoP1OT?G;ZjjbdUGO1n1dc;Xr|?=2Cn); z!QY2^{a8C@j1Z%$crjytft8cDDNMRXtfuf&3Fdnop`rSEqdF_zmr=zBiXcD!T5)-@ zz!lEkUm;l@AeM$@L_Qh{%QF-9chc)?QbrZ(qBKr%4+{vzJ+*+8l_z)%Yc|>i-_b^D z70L5t!v6A*wA0n;PmyHwg(YD_v zrSB*5GXo^u>0O2P8>RKG9;sf_ESqczj#^iibQo}POMbjXJ}`@+ZCY+%CltJU z03|p65XZ?_{lNc*8>-ddr{Bk}C3Ii^Mr9-Y@)p6%oWgukTfrmc8gM`LF@Hm~DvR^+ zCR)d}zJ_W|))ik?m5_DGM{_>tyMQ@yljZ^jB50bJEku5}FWtlJ;P(AO;k!e@Ywxds zcpZKkpt1!oKD7@PgeXv8Gzr`z0Pb4m6^!OHkN){tK=KSmbJr&3_g^-~_mW3>?=#4Y ztk_u1wqpGq=60$fRb2J{VH39%7Q~f*sGR|B_44p>rC?u^qiFeYq=p9Ah%osz#w+Dr=3@kLc zrBo{`M}zK;w-O`ty%u5-O5&9~eGNDU3y!>?s?9-U27Hyt(`E&*;#C&ji#0XB=_zRu zEP2VaG^w#Cg-fdfspMYiy)X~?;mFgs=RhML3{%S=8JEyW>-?wBPpSAvXq}Z`8U7b{ zBCWJtjF;nS=x_Sjr7|0pdh4qgJ1cPg+Hi%m%5zH<^9C`0uEcE4r_y3R^isL1?{<-v zSToE_5vFRhyC8RjN3WLFr*Ep=#EU7ak;kVsyQOrG1M4R1O9xh7!rDw^ZFu#$2fR8I zd~2v-6D(|H4YhjkN^mUMh_@8e(30OpA8LNs=h{u5G$zPAtM)o%Jy%;xR~L#ydew`S zh2yM5wj9(nu~>l_(2{Nl_M)AP$pCpg&=1SKMGaX*EqC|Re6@+i{Wtx@7@^+KB?7zN zm=3f}Inej?v1q5ZI7NyIud__|Vg5iLZ`)vxX`PD^BgTkb6gr@B5Oe0{no9ZVkB>%e zH9wupf`wB~faI#d476+@kpCkil;5H;Q5$Ly(geQ$k+p%yQ-^M@AU_UoE#|h`$2_dv z$mFFoYTd-bEsH=&<(hD<=CCAz`9irLoiFRFRhdyf)x((^ncVosOgAwz8(47Z&|svk z{Fcxq1v+rLGvjWT5f+4kbSM3vc;o*sxTnvoJh@*b7I{d(rOAFQT{KM10nNNOxYr)^ zwSjx4^;6l61lm;W#L;(8e9R~srqB|52LFf>Hk63HQNpGo6ZLmbTm^|ETw-Uqgc~J> zpz+W;+^9qNw-V2WODHX$VVyjVbQKKPbh@l|4t zrQb2dtbG4_k^4y(6~{>NwvsfgbVn89juqP#VKaA<%1131l-e21w~Ixf-d{t$xW9SS zA!6+DldN8!7M7EMHxwKiBI%bgD{mKVp!!QgR?Kt8{Lw{XVIfPN_h);`q%2p1RN*=+ zUH2ou;4N2&f2zbxit}YcZ=_#c8B&Q)HIrl>DJT36huZ-fv)vVk%aKCGn)Zp4LoptRF%k}kPS)2BoSZ-@t zFELareCqr3e@}V#4UL`I&Oy>LtzmYv@?(SJq^po0M!LPz~<2drhg1{HtUKaa*glMk5jn1h;p|N2Pk(-Z#H1u_&&jd z756cH%gu3xjP>jPCS$SkhJl+ihLt!bv}!f z;@K(vL5eQe>00242K7`95Tna=b2b~q6zQTLo-26~WGPBH0Z1*OfA#|B`LIE2oGNj? zlB4Ikk8mk#IyBq~B9BqtdOW{{l@|~6`!B#orE;#X);G;pa`ilB$^!$CpB|?+C;EA34~ziR;cTtc~6dOfD{ZD{i^D6Eb7 zEhk?cX2$ZTitQSd**tLGug3Lx=xkquCk_Ix16U*efyC}2!VDxHb|B7mIG~@;T_YB) zi^AWA{7Ujzh=XA53cT8Z1NlKwjKie&fh`|`23GaoNR_o z-tJE9tt>s#!`+eSHEK#_o#1SJJs@y-;y9zxSWo6Cs!pMwQ)2qLp2=N8tfMQIbIdL6 z5(UnZE^!%LztCgs;>e0FE|$T)ql<7^t`%Os*Omu3?t0h@=IZGMMWMZHlyuB38q1_R+fiQ`YFbf*`fMu-y$#pg51$SY&e0vi zolt}}3I~%O+Z7XADl;(@%9wuj;2ubzdF`*Na!xq9VmKzF!j<4XtBO0p%Q5_)iO$3a z_7$k*81->QnBuW%`qkIrt>eZzjwr&ih!jqYlmoJ+U-&uGVm~o0^q0ycrrJ-8zxOl7 z-}>R3^s|;0KW91Qx1f#B!nA)bJa%o3p7DK-2mKo@^CEu)}xlEE4<@e<1CMMmO8MS zn4}y~W`dF>t=NKdB(O|1 zw>bfFvF+-&mRGNSYb+}}axs<=Il1o~EG+5ZSkC^l6-z4;3d$a|l+!4UBZ^{$p0MhO zGH6{PkHYgyR$@7FaZa9WX?QTdh4KNGO4|8`Rx0Dsb}O5-;72O?SD_+L)ZIMBAVU@M;5-w8hxGvNFh^ z2kgsZM3Onhms%1J3*lH_3L+hnnk^#q9H*i1o(EX8=TkOV>mG1Q#~$!08?6ZsCOAJp zj@#m-Uei?{Adi+tEJ3RmCZQP*tbbtriVq*~DuYJ$L7}7#d2aLi2T}IXHssN=l&){W zIduXNM#9dKD*ZqE7h1_=ot<|2OEbw9!!Jqs%f;BAt^|#9unJeUR2CjiwZK9+*TWQ;WRA2Yt4fTx8VYLdEM|-( zUh^Y%CoAZu^vH}^{O&Q&&Uj8Mifu`qY3a$uU}3h zZx}AgvBgC-j~|ylLcxEAZb}cKOLEiUig39f*tK>nk497rLs*$n39f%Wa^Lcm0@Gc{ zcm}QqmSs#k$>c!yv=s|Rl-apl@7lTC=c-eFrni(Z8Eh9}^L+N+wxxB-&q-7|>lM>p(CC@Du^wo`b7zF}7P@L^-pa9_U#_6}?v*vJOh^6lbB)O^ zDlN$^AN1H+ldNNGXgi9JiivZy`PmGi6*VvY*uNj`d#-h^z_aY0_X*bK;ftXwhbwk2 zpYzauWuDR2#oF5%qg}+@fG3K}wn*=Pz+v|(bF8;}9I}x)2X4MFL|fOlSb8_FGy&(m z{=*gZ%iGJ_dTe@(DeiYHja+G78}g`(6|Vb7^i^8-LXV@1Wu8UdS&$?-c}M7`L}iiP z4DDGcI2Lv(YP0)AIh9Fv*e_M6yq;?{>oUA6WCH;OXU_6&Q+{S0@Gx13qF5QzT8cO( zNE?oA$^yM!q!xOciJ0i~LOp%L8a9JIJ7gf%iCx5yn1o`ddUXr}i= z!K$!y{cI-HyAM|+igjos%TrrXUvBmg)AmA(Xn>uTG4-MTL~-l#W99XY+tsfr^Q;Lc z4q#q9tJa;MSREHSfV^b2n&w(l)NDBSEUd%&mIOIgcf}iPNmzObd>|ii5|c`7Sf1pf z^fJb|6LP-MoLV##95LLvJQTcjz_=n5%o}j65Wtsj8Q8U)VtGDdh<-gk$^(6W{(Shc zb}f&iu~fDM7k&RzJ!T~0<>;(*bj>KMbA^K9@UG>=NaNece1|*&5mt=lHDwOjpxk4{ zm?knd8aKtgAIgJ1I^jr#O2iv#<$K0$&V$bV@6l5^BDFVM9||>6t5G-Ljse`fFIP00 zw19ly(5~f(a0|CW`_LHf!(Q~k;DLMt%g-B!l<(SH*Q70$U`ZbrB9^GxsUo~5DYtum znQG0G#21t(SVh+l=D{~3WCwga{ExdKvm8L8)D8|+4%?~6SrJi~_U&iV%hJyzs zojYY&>j3sFtEq&(LgvYJzud%EPuZU!E@Ki)zgak$A9?&8F8=PK)|s;V{>ipHhoh^; z!N{eILw3_BKgZd*j_MEH7P%ChamM3ZH8BdsTtLq3-?^ruIDk5k+u%~M_Z(tv8YOF zZNwOfuj_0fQMCTNL0Z3aP4t>is_b2y*-=ebjt(_*A{0E*8VbJHI-{Dc{#0GsWsjfL zDmbH@&uS71XjC7GFADRvWS66Q1u*D%JR(1a>jmtLj78`s=l`BJcM`~SeNFrh0}eXenMHRX1xmI{a2$SpbIML&0K>neD$ zrfMdg_eItZVhmvZwRxJUluGSNh_s{BNx!C+ZD(~9#-Ah@3aD-PgSA@6;ng>-NmTx6 z>lqQ2eFflxTf3xZ2FI3rYju0h<|?H-HFV#XYfcvn!?f#>TOHy(8eO*R>R zE2p}|fauLXS>inQJ=m*2#J zrbmblkE6N+JcLxcvATa2vXrO5dk_kCg!=p$;TgDYxEGiRucJSJdxiW+cnxU}uOXE4 zz#}Ph&H5$-WMK{EdLH;rO^iHohOoEzzWZmG_o>Ir2h=#=8p@}{bb+^hmMJmAD z7$-A)o(sdSOu3<#Q(1$wQoK^UsGXV;#HI#Z_M^&$Y3%h2X2c#l5?oY1(}QMU{&vYt zs%m5DBTV-~P9_eLndkk>#(Tz2DL622y;rPGa8R$mqw9!+nQXXQXmxZItm>XSvzo6~ z$((8#!%S*esPV(J)&9kTF z7G~Vv{o~+;PIdKS9QAa5AW_(rrr2@~yl}s4)>hwAyqHWt_Z)wh@)h*S zfHVdDvNmy|c2@G3l;j-VY8z}i{N=S54~?abEx(==w3zKcZMn9CP6TdI?b7Bfi;X2@ho5^%LNjH}8P-^Qe{ ze>h{P+kbXr{N0Pj#ub>WJp(;~d5qJsd7-2014m3Td}ru!-CRp`1mC=!;`?S#N!BS} z#aeZ^uNAA0Q@B7sl!lU>tXSF9CT+UukNO@jm|vZM`0+8m#B%47JDTYeum12N9~T9? zAJ;jje8v)kICn`z2CBr`tmorIj@lT9tzr-SP`?RvL88zR`1M)|c{YS7M#P1aM`>(# zyk_tOrDaO%`Av>$UhGg$JHb^?0nIF4Fow@P@#FJ}t)9osUtqxs;gB~w=FiC};i?xh zY_}u9Ah}WJrUjI{Y?@;X&wK9>;xVcjvsPMfvvjeX)1qpC4~26#P?& ztxhP8HvVUeL&4rYOLc4sYg)``i+0S}b#2C@G&wexQ?@$d+ad4Mx1rzzfFRl!T}&as40SkqNy7X& zL&5!h>XNWL5^j}_wE(K7_BUET#i_lT6OXEyGQG>?f}K;z%z<`CneYP&43 ziyo)=r?CAuE=YCR-`=pbgU1C=gcNX07W~!R>8MX(xFci!Io+*xL-_9W!aG!{@I~M*p;FHE; zk!xEYnX^qs4MpFfvTLwt<4qhU#rfYUeg(blb%0CDmV7&+5`loYBRZwke}F z+q+`Ty8dSrZKJM#{cv+2Mwi~MyUIr|QZnS*ZzV$1ZA2)=b;*q@mrsP5H_~ieE08{z z8c9D#xowKREfxD^R9-fd^No_-I^s>+e^bV@tnJW@II}^N|dn?=wgspY_;c{_v|=U5=Oy z%9ys1ot(UmQ)eA+KMc=hv>KW^H8}qc{KKC7CbzXzT3cQ9g3Zy57>gkv8tSUb2_AvYlwvsNagQ ztTbZ%(7|>b3Yv$X@{`Hydh_=(_-5)}PF&i$={wz3Xnd>w4^tV?4CtZYX%8Bz4z69&4Z9onooF^2b(QBKEpLfQ< zYPzX}>*7hOjan>V7m#VV|8m0{;DKXd=CD*&lINgbA z=eipu-fkq5Y;sf$Ewi?yzLA#s+D)?cr`D7(rZuw@q;xUDsaW~%{TC3`#Y*$aqdgho z=0cMy`ozlOkHg$6rJVC@FC?Z%;8{4>|F!zw6BW)eun6jecLQqOPfx3Q<%EdEe|1g7 z;{R)0-M19^KI(}cNhTF|f9Xt}pdJuz-64LVOj$|b3n;1iopQ$?4g%{o*;ey~lD+at zjF8Of0b_oRZBmw~35+4TTWyxK{@MXjw-7YBZ-CTaNDc)*9{3$N32S}`y!dI{J-PNz z$}jgtq#Rm@5&my#Lw;u{)xr%3+qa_(<=Y!^{fRTxPUM+2q2RVu|Hi|rcbgkFks zEf$Qqi~MB5mr9%aOQro)@alb6G`F3AZy{-+B2=D&*CoxSXi`ovmQiwu6f1(YUWv12 zf$n9_m8J7d1poYMupaF|ieNN|a(c0!mRJG_Y!j}{8ukQhq2Eo@Xiv~LH{o3Xcz-q| zgx@_Pr~{1p1K(&wH&L2B>!bZ3`{)b}1wDfu{x3D;LnA=FI>&F zldT3SGjnOS(csif-5p+1kLZ@cRMUhmPJN$qEGz^i(7%7_WCmh#4C11-t{gg(N`0&> zvvV?Ifr0Y=pF8W6HO6>gM2%-v|9s~n=v12cMXQt6ZdAvg_)?km!HS-laXZ(ZRtT(m zx>(F?7BOYS))lM&40%bbcdniW+zH{<2Gp7p_9D`)1^1iQ53?R1$cO&H)H|C={q!OV zTfURNAB#0Oqu(7a@rXbpEVY4DZLM$Zd9=c^na2T7QoqknSFe}*{pa(a9o{%yx;5EQ z@Q!_V>tr#l|7m3g-mU82oq|}D{@b73SnwxBaCe+HI~U)e*LA%o-btf7mt-m%{r!B( zY{8@oj3lApg8tw3jYRx)bVug8?&|qntVQLmSWCH@CZS?=^ZAOktXc6l@awLr-l4nN zc3tmfExjSwWHcPr96nTf^N%XZZIoYph%4n)MX42~LR5c?1cZdd5q56^ikt)mjM7?ly-6Nn|E zEz{^Qsx4zJ8;Hn}v9l2~A!Ue*Q7g(KM&dt9K4v`EI2b%SM7U@zl z(q~_gsFmvD5WfGB_%-y!l!n-^P_S5e%$WV?U~tcnNi>U(L02{^AxlyT?1?UL?c5KQ z&YT3-hYHCx=Kh~usdN+_-nnt_($lV;pp87lK+aSu)-JzIJma&H~3!@{(rph#ZurX^dfd2^gc@M`aeNz!V5#2idm5p zA?LvZXp6Bct`uUjyN1o~2R>ZQKE{e|N;VTa!0@TLKVPQ5pAS^2AWhf`pkX{*`B@{A zvtGH^woG2fYckd=MYe~lR`f7Im6$lq z0E?X%Ta-IzXfo*+HMna~V&`7KHxCxm@n4H*DGvK`sFm&3R=2rqcA0ZoX|gL*`iWRJ z%P!m4Oc#f8JpyJI?-JAyvOlIObDnJXOyuVkiE+XWdn82ox*0s8FDO$_f$`%w95 zNv@I3gf>XOS+MR=JEGf>h1KhTQc6o=Cr!h(wz6cY;p*vC=H9k>hn3S4k0IF+e@^dV zPsUC__S#l3r`*qI{q7e;$eQe|>%o!ER0q-OWkr$WGWYj!`|Fsbh9NXXj3molGv- zdex8ktXyVmub+BvxFWho>Sqe&FIJyIZ!%M$&p&dJNk|fBD8k~` zrC+(WyLJTxGTYVZGKzLZxVK*VTAJ>d4+^>`9I2+*h&=mU2DRif&mq={Mk8ymgTstHB%$D* zP`X&zLSxe5KR!q`(&6B*5%ogtVZ8i$KS}TF;N|STIf&)v<&XQ?9Bn%6m63nf$6k&=6@0weuIm$&LiZP3{W6Z3Jg+6~gEQt{d${XOC`$F4kWa5v+dY@2i zrjACl>m$WBgYE;ZY`F(o-)jMZ!7OwX;Qk)$qWGI(jzrQEIzC-+^dhTHDA?x`JYPtE zam7n`8>25M!2cqNm5H5oEOI4_w2n`c7vLLx$FYm7zQz^hX_r2R4U?7^3Jk8f5(Cc- z(L0Y67EG<7J&{ zuie^iMSZu0nt+$QqqOejAvJKhp`71umKvlt?U~2Emg*42rS*I*opM>E1u44pn3I-* zB}uNivt8p|H+y0g7lGGL36)906vqv0(7H3=%TZd!Lp!&M*?4w_4guev`BTNuVbLLu z9d@eEyTy?rdyK{}$j^KbAkjHp(Oh&Fqq*kO-@><3pAprTpKWD9lWPd2$WIK}*o#BV zFWa9Lziua)oscrtglK$ihj;B*8(R8o7!fVZlmfmhnt$DH@$O3b8AeB!sV(?@>$xP1 znuexbDeWowE?5?ARW1>`;Y;XBWG_L#@^6fh4LzGKHDIp_tnknAmd>s%Gue|i z&|kblTWdlb=quRA%WR<@U~1JxR3@nX4n*40T~+dd7)dL_SDaKXk&L7c!@?66+0p3* z%^2;=(&w%*(hfuF!nc#h7rZ>D#FgwSkm?ukGAT%P6u7LS{9Y*d^!wBv^t?Ul*bc*M z$uEUV)x(xU92Kr_{WA8vQy%kNf1(vEu8A>&E11#|5kdOEPp1+KAIK)-5xp=Yk01tw z#u)tZK_X}4?mcouX`9n>As_R8+`H6wnQk2fB_M`C5ps?z{M<(nYd?hy2A75Sz*<~g zxE>+&i^1Tc)^u@>B1}J`@HvCQ`Jl~Eux{uq>^l({1iDq;H{85HIgh zRN{fYXlt!K3ib#A@!OpId#sxM9gOAv8m9BCgq?V<%9g{3H)PK+(+|U9O=}UX4)_Ng zE>7-mg*DWrl@gi-#C%m2Iwgav-;W3}ag)dGsYOhEvJ~wqk#^dneDFx2M3#p}tkv23 zeTdn8x3Z9vvOG8)!o@b*;T6V-35d0gmN;pi$LXQpfrGLmTa%V(&JoD;e$gWSiI=f>S?@2O1Y!)jjWscQfNdTrHlW}7hr+AI6Mmd0A*N%{J>3E9MBFnU{zL4& zs^jE*M840mGCPP|p{T;q_3$5p>A4c4Df z@ay5X$}`HBB~uR6UH+1Ng74OpT+t*-@N^erpTme#zg6t8EV0~ExQ2rF4fE16JN@#b z;d6ez;MQcFhfMzFbXNI3 ze~5IZga~rebNm0Q;lzCS!8nCUVKOJ4oYBRM{~yiUjagoHnnht3bD4&d_iAQ#sl-vO ziD`)}Wq#2v`+3Si18ZUW~g)7L5qw#ANIUi>o3T{XTtiWg%O@+|G&m zraHUEi;|^)(n+x2r_N4%`WE`shrY)`aQdp=zQk{mUlRBOu{ zh@SaiiAfCjnOq?+E%O4NAP3LA=r4kt)m9EFZNiHG1}Bd|%<@~U>~+FGs4#Q#IOalZ6kx0Ht6HATHf=>z}4KqlffY5j}Ahgh$r z>+G-oj5zQ=wNiM;iodiM$s2{YQEsxXJzUNv-(QQis~V8^uuh9Svd+*7NTq+(Osclw ztrULiUUBm+sfx7gmY%}fN*&vp4j3YNq-wqY&A|QW`Noq617#SEcWR>LFS+@!Wu2@! zDZc7lsPKCzhJ@CgB87L3nAmzdG{X>L=4^u+@#U`$1|HC@>wSE0vg z@6M1lQR%HZQ}ZQOOR#_WWhE6hqbQciw0jLQtF!wI;WM7F8o;Aqj82eabOpc`(IvL> z7S6KY9&^ed3%b|4Ikn)s4cfaAy8re<=B_^9)B-YrmgK!RDQ0^itzW>%tuBREOt;Eu zXiXFU*sY0JBr4B(8z508_t`#Z|pz)Wa4SRLDuUK*_h||Q!Maxn+y4RW;#w& z$hr<}j1|9+4T`xKU!%x(Mh8OEtYOSqBwC7=|CvblGA=kpA=)W&buoJu7bHwq)$Qqy z=9ryp>~;1#TK|TKVAW3gb#|-Oa_ruRQlFd2Z#7HfPH{Uz4sJVh`!ldK=|l>d#=9m} z<(rIF7z)|TO#Pvm(Y}|JF~+Hx$?YoKrNWA)2NmU5%u-T#j&Cl!6){pqSZoglLU*Zr zds6B5Jb1u%)X?nDu}~jv(Q8l;kqVGVTPTD&^+qu#V{9uOZwvPIyg;w`hTLM2?mWXz zh5sm;*0jCw=QDB2%qh&2`{tmsw-60MsmeIFs?+S@8Sw6v|{!Hu^rf*US9mD(3ex zozQD6V=<4)b-(iMzh+#q#7Ac&osE4LScas7Uo2jU8na}*R(;B5cj9?T_Y5Yjf73t; zW;pLnYo3G1ZCF0sfK`aL*s+dg^}X6H2(X|kw9MxU?(? zu=d;CSO4q|CigTJ7BqCLwD$q7XFE@V`;c`MZwBmkKf7`#<%%nQ??vv4m{vpMg2oR< zZ}!vvCjUo&(`B{xU|@lc_U<;U5G%M-jZvA?+M}}a;jiK3853^9Z}e@qrPKPg0Y0h& zR$InPOkeqF3;j1*a5uI!_WIN1QQBzO^&^<#yrU_m*fcN2Q-$9NjHaNsj2Ad{>MfTd z6oIEUSdjQt=lpcU#+xW*MEKVB!sc%TOS}JFalYRno)RVeKj2U9b(eyU@<=C}*U`Ab zKjW&JP3~fKclAEBw};jNDq&EEwp)euZomCn$4wqWaXk(^F*4t2J@KH&gQ9n4R>z;Z z1@i99kFnQKRY192hL5SwDi|ZK`le7UL7U`0Re)7lq{P+*rm8Rb$fQPn5`Na0ZzxhGOc`UNcEB0iRA{KIuM%)OSOKPhH(UzFOQK{mY(fK$5!7OG$t9en0$~-6@ z#<>U^#i-NP+&weZkQRm3T{ABor8`uW-!!8~jQ6(OfdA*YS0LZelM1O%O8@QV5{(!u zCQ_}h)$^@Q%ZzKnf8bkv|0tYlz%!091v1M=C0mVuGyKku6Gz4$N`h=8E?RlV$~#>V zKMSNL?G^ul8{e`2D1dz0<=^*h+mo+cE~q&0t@tFZk3CZ$^ZY;kuUww-*Tus!qr_SPg=j#XkWRU^hDvJ>;Gh$>xp}SkmepIMLxZXXc5EMY6pZ657`x60pWB6z7O!>kcv6j2);7 z^C>5P5n3;963_cb-hdr&R~Wxlqo;qZpgrX~B5;e^`wMPDeaY7Veoc1*gu=fo>j;@L z;aWwEgSb0yTXT4Z!|+EU%mE+wA`$mrUaNkABex;S@dZUgsKh=Zpdk#jdy_)a`O}aw z=)Q8u_0ie=KB`kJ)?5$kE;vsPRxA0`Wj`yz4%hUYJwarAhGcz9Y89-6+1GsvbQvC+ z%qVdhcD9XGXkAgzt*Fk@7}jjmh`fkbXdZoM=u9Y|-b}56m9S5oAL7SeJayHtht6`3 zVg>ih0YurSXh~{)S)!2alc#=nL(6#@*Q5R~E~;|tljn{-WKVCME{2jX7;wfV-oE+~W6Tr=0YU1g;r{`Ck|P<3$?l#$zAeaPY688&FvxIhXgq zb{4O6mYd5r;}p$?@@Qety!fw#TmNIw!`I@hO?{Iv%jM$b4EQ@v z0D8Vd1%DHhmjH`L8Kj?puix)Rxhj+waQcKl^lHG!EwC?`A;2OM1#3X8Xs%*2DZIA~ zSkR`*M^DS4mOfZQ4^jUPZA;%2Kg)u8$9m)7H&IRBX-_(-bK)GG04c+6v%H=5xTCxb zYa}dFbgv{Yrz$v21$H=Io_}K}GB4|!^{5Y?K!Hbk4*OnWN{EHVQ)9Q1-sGYG%xq%>gHdf(K@PkM`!6rAR#f$->H4e-?aVH~DU;R{3y9E-G=Cux7UOy|`ENWwwFr9g zVj^rp@*_>X7kmDZXt`H#-Gg#0+R4MXVYkM5zMe)M^L6)imi9gYe{ft#HMZ?)u!fc~ zh06qLq_KQDxq7+g%M18I8ylBMcvB60(@7!vHOqbJ=S@!*UB~~gi+b?Cwn+A;j!%b- z#>sm_yh*cJvpW=IL)nvhec$+L&Ar34^&>TWJv~Q;gJ$!74fdvwXN}JS8#s$4#K~o_ zui-onSQzz(!uf=g2SeDoYi+QPZRhLZQ=xnm=MnLBz^RR?PpL|2hVOW1N>xJTjH~e+ zYtrl{6W@kR844aA7U7p=0MWeAQOrf0gc4$`Hu?3^?Hv%`;Px1QsMS2od*)Ya-J4tW5T3Dmn&h21#g41Z3+%No)Zy-T)a(sA?#K;gd z(5%gNo2&+O?O}{94!4z6L&o1CPVOX=ZuhNBz0Irn-MEsu(g)4kL@jolaWWITSa=_+ zuEtv{KjNtE&F5-+IY+H*vYH2d@%w-olO8q;Cg({TpV84sckb18jh@)+ zQ1qgqGv7q!?Cc@gvnq9jkJ7wmH*1Q# zFBzh6{Anm6)zO)j!lh(Ifzu*VMLt90Rpid0r|oCGMN?8^kI%#q_+p*~To(K2ke|?`1K%fEx>K=ES|^J$ zE9go}S3v4vh;kZT25C5WqK`2{K4FX~@rOPp{afgd8br?0I%pfTJ=PiVE3)!O%`|_k zv$84Di;ep@`L4c{Vm10xg7fI|_Zx~SP73<0`*C(6&H`|RcRfz)?kc*wh^-qAT81B@9tiOJC9vrVkfJNm>!+Jbd%v2Zn%w~o@D*k;e4)Sr z?f+W9@c^zj`~RomfAycfi*jn3;0aCFc0~He%DLzrAMRb`oC}Hx?4L$iDpQFD(7|I- zr3c^#P~dwsiPWPrn||YE?j)10`Isp(px*Ec12u?PIoI(s~> z46fsS{lVXX+wkI8oESA6EFK7-7)2!?(EU}vHoRUt=|9e06}*c*u!Zv%{l${IiotsR zl^@;-j4I-*jOSoAHt-$r7V%<31vI2B9S^};v;z{3mp(6kh{iMOZ3fsOgQYW{=f!<} z6RaD>NsZWFsl{o)Q}@{0Tgmu_=Ti`A9_=lAep2JEhY(-ihzN4`{Tm{h0E6|?igVB7 zoLpQ*7tQ4D~F=KZe~oo(B_iLtq;K-g2Qldrb+)U>}o6)w?0H| z9@J*=9KJnURn|-@Hj;k zVgKdoe%08t4l*9vl9s7|+0Gw5Th-wi(Ts0Y4HXP@vikDvgPVVr%*4!mnO1zZeAww%8~7c7@^p&s^3^@%60#>#AMw znS2mwReAW7 zs#@unTYY&|kTm6xW{Q`&WfJYfkDRHLw}x6pDw_9KSm6bO z?P{#%6g@+U)|J{%&!~}W=)3yxyZsg1sl}2N_`l?@FK3_?Y%ipxZ>u~{Vdc-_e>C6e z4>rXj3c#kJ=Z^dw`+lGISk^3ErH##x%UKpYj$)2Y7-}LRZU+~eL z<@BV3S}7L(UrH~jf(@|T+ou_OcL$kN3csL@B^I1%znDy#;?w8x0b^8wVsY`^wOo;y zw}h1+?<;%$K;Hz=J_E^@Qoyd~|94~W0v5$}{*RxT*hDA*!#$b~s&82B~HEC6}A+gCu ziFWZe0}Jf$^Uk8Nt^Gg$eV*AfGv~~iGw1rA_wspT(TCD~#S-;DKJZot^`Au@)W3?Q za1Tpv&RGk(Kp0#A^q`J&m9?ItK)gO|>}o4-kiRnIAxA2%Ce5oKk)3n6>(VPX8r( z%nv>);Zq%Xw3n~SsQ_2gJJ>m<^a{1kR0iE~9eO{d=}`5_8s^T%|F&j2S1ANS`Z)*6 zHfv*`I&8t0T*5{Sk+(}(r|J1Q9Yp&FHimmcH6#o>F-vG;0k-kLr%c(2@d=LFh_6}} zZLY^x)7bI*PJ&O&MPVdIUeTy5;L~)R0{z&McmS9gG`}P+!Bf_N_cOHMO8sY;gZE-h zpz_n$rM>6_6P05`9;jOuX)szy#@&q4y<3=)WMEW_9;@e^drWX&@~| z@b=Mk+?I4lr3CyKp=OWt#uBTvAz&AGKJxJucRaXK#7*(#N|x4J^NT`$QC~PTZHWi4 zM>e%Ywui=jkDRY+Idi_Klz;ghQaJw^NOAqNr-(bguPsvd$mTbC>r&@^1Ebq2QN4%1 zc{lhqB!fm>`gI*auv!0Xe_ z@4$Ix2TRRE|4cCSgCSw>jxhgbvTScr9*sXPg!q#JS*#sPeD9v*n7tx zW?js~ruISLalYk#``UBsqEEklZPU7uE&Hx*TB9F19DGPaVCj~OjF*4?_BF@4Ot1ZN zWX>y&0)!C=6KLLnjQ>B|KlS-@&xLzu)R}XbI}436OQ^9 zZLYidbZo*^dj2;0l4D>Y5aB!b9M%@BOL3ll=)qX8CvhWmC(AaQrTXfSG9z?Fvr2p! zyC}zH)AF!>&b6a#gr((RM}Mp_Lr%ZCp~g?Wr+!1VpINJXWY_(QBij2mth#9(SnbIK ze$f*7oU=`~l&#R_HW#-M^K~}zDY+F|tqbw!f#swY>QD049Twp%XW2hH%fqS&GES$}P&PNis zUevR=z_e!SH+pT>z5}`&T)@*qJPQNRL@h45zM`RUvJ{$eQe3pcXUYqJ6$px}l(;?* zcjFswW9LZeTd)FI)+RP-)DX_Ynz8g$4fJe6%B!Kz!8c>+Iw@OPwE1_9H)cPR@5i>* zfr?;6TVV8Ff?ioz7qjv`Eq~l&*6+RbXuaK!BsT6@^2x&4pnvMMwS;iRb~x&**_q!| zb7TJER|yk2|HJ3lumGt@ly%IpcZ!MEYsMGS)WlVq{BbmzlRCd zts4Fx>23%z;a+Hzg5>mk=(bATN?j0I4#1(!fwor`^u4GR&Cup>%Uh6ZoQGzqy7!P{ zidzmTJKrNJ{q}v}qotc|-HNTJ_yDZvZM#$XVcdjjoaM{Wa)Qg8`s?NMT`YBn>$EFj z`TXUlmjmIzHGjpB6;T$k)FyrA<}A_6bMQ^urXt36v61*Ggj7Iya4PJ`quFI`z1H4; zoAsHs|6H_7LFmvyeqU4js zsKrCwqcFb!V<4oLKJkD19QYB(xKWFii~x17Kb8PG=bNW?(p+f{=l>V~>qTuR6QsYw zLUnNAnDxs7iF%X}hzSbVQWo7rt04RdYMFa&*MM+LabNTVV6S;MG+PMy;eOjzb-qam z@cL?Xp}F1jGf$Dn0^XQeq7{=`B&2lpaF%Ly0a7ktc}H<(9@A8S_A&$cfZ_@Ln6T+D zY1G%PF<-S>b(y4*Le0n`qA!9^YAAH}+XyH8CKDi#FPO=(QaWWYmt< zQ@`1~=aDIm#~*Oa-9xjKi;xUocI>I<&g@mw8n{s(`E~7^fu8XT*aY5V9wik^+<1%` z@Z1&mN27!40jafH`3dD_<8o;9k?#H>^a=|! zwZiM$gUzm^`JQ7-9Gk0pS7y!&NklVYLR85Mfm{-q11smi1$XQjq7mqPpW6f40ent( z7}q3ALp7O4s3!U+T9;j&<>U&54CSPdaZR&RzUVd3Bh9k|`4ku_EbwP{y&Q*CbPiV06V9z_nN2wG z--s!TfSAH(7<&;@!U!qUcW=c_sdat0XrgMzqqy6Rs-{pS7-eC3;4`LFVi85Ir$4@1i)+jwi}u2 z*Bh5qzfnzn+afQ3{y64k&^X~Y6P;fz_mNoEG%w9U?}SFfMuw?hFU+z;ArIvzs+<51(hnc0Uy1ts$e>>KUot^p6D)xH`qvpPlHe$8)@*ki9NN!Ev z;FeO#OJsY>E+>^VxvTDBW?k!@3>nr3uv*GQ&uuUz%Yr2z2t*B2TOYE4KNG9V&@eck z2$i;0V{b$6->M!&I(Svl(wULV1#dO9XTx!awYY|9PLE_y zp}J@dx}3~9!Mjft8w{n!JE51IHMr#7q7%+bSYQ8W0GBJunL^+48B*pQFqGageI>Nd zQBTi?`7*>MA-)XFQZ{^lu!H72=wDpnM$?=}bEkOcPl{T6nV5x=KzUfDx~VKpqXJ*R z`mcM*|Mve)oe=p|PZt+&QIxt#YLwB}y)5$_E6 zKo}8MJARM350-#E2efh3;HPgR?n;dG5S8*d?^)-Y13kRwuNo%kAszVK{S|aigwG1bm(OTw=VOL?o7#n# zEc|oWCBEm*l38F^2Lqmt1zO;`#4QeJh$eRU_?lRF8)$$AH78_9`RfXIB!z$Va~VJP;mXEkR)UjPXWLc8LtAZE(Q+TlS_V!HEJeE!Z=$myA!dHtzdoZ( zdxB*?_-{|#gD2*owQA#H%$bmD z9fpUD9qw(a!MtO6jXx!0j4xtj4y7}1Ez0&4K)3v3^{3_?HT%^?=ACP6)Wx=wstkIv z$;-^!roN3Ql6rHE_w|K0EsCvC=e4rT{a(&|5%I>}co88zxy#F&zeWq2u@hVt_$e#* zyQWg#49t9?AuW~kNA!?kVUFq~&s*;Kg^^TR*aK)u-6QjzW#%zGA`x|7b ztjuw}wd`EA?%INt^@~g;z$?s+DFI(;3oK-86C_P~8K@1CT%kuP3`GEe)r@@wtPr~Q z`DaOUaW*L!A=QC@wH17jcX8~+VLS9x!&7qfbW_SN)cde%$e@2+K^eLc--3FjXY{aP z=v1EQvf^rTH+ff}=T)p3IxF!wSOC(jq-56rF51=X?Ep_P>FcCqsmjs6#m)o^Z!2>h zYc#tIt%5~oE^$R#MAx&fk6r3f@vd+E;$7!(fENM$mN*xu0^uu%T5JHjkzMeB*LOki+0U$&8{e3z9_Jc-{cZfKXuttqn1adZdz_^ zy%B%BqGtIf7vCGlQl~E`RJ0qhFI9Z(3O`LxQY@GHm7hV=i`FzkH71$jMmKi+L(_(# zmxv<9NPEa_;Zpe2nSsc@b*^*ES!}0e-||-1%z(+bZ-w4mt+LiduGHnF%PlLa)yUQ* z(8L&UY-YeQ;TXx>`-Zb%e2XO|_crwyZ2&xo71!D^pgLt?~nhWB2M|YZk2; z_IT;z%kZT6SWIEHn!@~#FRQ3lE$*3tDDmOIx`=8u-Bzs*byusYF8i=*by#b)n&zrj ztXA6IaoCPktE1Q@PE)ly7O{D3 ze}xmf+iGo%yg0rXUIJlrXhk~?#vx+gxVk9>y%Hm>DaGl9EO4d!O{^Gtq?GY=-ceW( zLs1EBcFSkYvxRm2PvF!gon(I&(E~ljE) zeAl%e|3|v_!!9ShNlGcP;~%pF~9t!(B_G{Mr?t!w*?Qkmz>6AB-6;>@-HXRq8m zE0)eWv3tN+##g*>0$M{{u4%NGbr#x`TojcCUgnA}pNVegIV#5-l;cPX&Ej;54nj&S_&%D6cI0r zIk2=z8Z8}h2=Ct^UH6&L>NL-VU~9qxwr-mFaytHrT{84NdOhBBDd)R>^ms!U<`FZf zx6pHEyNO3x2FkwPO%yf!(H-6f`2g9wvw#=7mxCQVthT^kgO4*BTUZ&kTj;2g#br2*DCW}|osdg__On^2te@mrBEycWKz2^0IW+wnf4z2H=e!QS2k3w6Iq#U8 zX;_-gdG=-s1+8z=k#o9Rq1vC2uZP??=M$;XC{m1Z=hO3OfJ4KD@CzV5^G{F-?5 zH(mQcu7E6X{)(E-Cd7ysUz8_%_&``n{vjk(9`T%eMt~KKkl7zrM?>MqE4nom@w|6y zk^aOtr&t>0nJS&|m&wDVBzh8)XkLn#h?NII~J-MK{ z7t2OZ-Bca;fGlu7{8FH7IVf8WaRhVWtuFxn!&41pu{p)NQD)h|y~r5vt#RDxrM4Ih z4|DM?IWntVDWl!S!rrWQLd9pE&SwZ!LKxo1*HTgIsX*>TP3k1$X?iLh?L?#FvMjum zD93qZ#QqB!PP#XN=@D82`d%C(e7eU`1k2hYjG8#g>sP`SI9EemNKVPCK>pB><9SYGfKj1+)LQu zU_|R$xE(-;*haem^1?^s@6yfjml4(<&^%6k8iAhhC13Fp><;?{coykRtZ0FzM}Kfz zmj#TB?D*&(eHy!fnueF)ca3G-LGX*e24{}hNO683;*jNTD*_IW#;-ORMZ~0TSEbdC&1*y7PQVj>NyiClH}Yb!!~w= zc1v2H-$+kUKZ)~YTo8rXl773kn?kK$02QAny@5GS?!YtFZ@pd0FVt^P<8@On`MZ=C z)E3l@UZ>%~qR*3l=hF?O;mHE|J*XXNI4tJaFA3Q}mu!T7r*0do)$creo{xo(!Y*Ah zf12M@v81b5FGmKD8vuVdI?WX&;cKgR|+U>5JZ$gV6)X94z#4oGl1)fB_q2>Sc4ctrj zdxY1(bHF_LW8XNdy@UExr#3@hxcN=-x4cR7$(URNoarIb{VkXWHNS{Jn>x$AM%udj zyY$J(bLTdhcI}*=WsmnV%LM1xRzg|$I2)1(tJA%SG_4>>KR=SuggcK098 z>n%obupG8udszBJa1yjV@y1V7UH(`8;xt{*ur(|98}tHEPdn3SeS?3J)TXU~v|AYr zO_7k|LrcfD2(NS72~)@n>LRiQc0XySpCLN{*LY43 zuav|`CzQKCAvWwMY!>G5eOj&5KZ7+2Pd0(x&pWEe%tP1#pil5@6rK$!#dzQD=11gO zq^w2Cy;?5NLy|s5E>&o+AY^z(`1m{bOp75JmZr5x5ndY$4|5X|A>XNAA2>^Q;9Kck z8tXcYQ?CaeS1jBXZogq`c>UoEF&+v3tGmt-(Sly?D8rba<0Q0pmP2bzP`QS_E@HmW z?Wl!cZJISshGY-$=u}dCWG~)JkB=$G{hABIdvY9m!@kJnC%1 zlfskG$2lG~twYHNpPre?H-`bfxjK|_J-o&25mNW8NtJ8YT=CbhY4=ke6eR&^?~kr9fZJVwLLQ{ez`n)6xbG#X-9)ZU#S87?ujzP9kijOPqnDv2vrQ z7U;VJo_w=NJ#~+a8SNPSfTT}q;>>fLzg%N+{(4P3ZK$(z@fd7hIIMJ=by{dp*$R{^Stpa_#Ut~ zjPSlLSHTus0EgPhB3i9d!4iwJYDpQ8qER2tJWzHVJl0Zvd57+Re@O7DZX?$`>46_Y z^c0~+faOVIqu|z`WoGl@uxt}`Vlgk)g95WucPPU`2RqD+bTsUaOK9H#tWC?G+L*XJ zpM`|Mo!;=8@*!pn19Z}YN+@(gCyl{dQ$MujAo=9~K<5pYCGxCLL;Y89V^7oTMae{z zDpR$$l1(vv7xluw_s&c~y#2;(OL(>Le`6gfjOz6y$jqc~G=PEM-n_ZDEcDIfxiP3bbxT>o z7#^x}M;A(S8_sWLO@c1+i%fWf?E7Vyr>ZJ_f%@w@%CfGU?&Xb!e%|Ea^xGv%++=%Ut{J`l?&Kag)yq{({)gJb)W}- zh&UvB#OW-hA$a);ABJG@v4A3h?{T@o-?SOsQ>HHr}I2jPYOV2Bk!6- zJ@ELaco%fFZr?jQl#9S3zSvmj+3=(h-eyLdf=Zp{J&<+RhQ*g*ME_bQ3ulyl6 zoypka1eF1ytX3P|$Sg0)3*xyi`^lr4>K*;h^pi81{+SRr?FYXJK8yqY8d)d|pY@%d zf!a*#G__JciEVvR{-vY7jT82^3A){FI_^d1MV}rXgyE63^G#=15~^X1tS6sBF4TJ} zywugg0~*V$bsEm3OKhkG)Z$KtE9QI)Iy<8e>jyl9w1o8QC0~ z9l`pyvepkbG0}wZh7L6g@P`STiFhT1V-q8#G!bHrIy0!)-i>VvD!yQRE8jj)0A@k- z{33SwsC#$2s0%7j1n*PDM-LPkPwI}(2QCF^9JF;!(!%E;pCbMSG%AyHZ3Za7vHa7h z!_ownSu7KN7K@y#8n%Fw-ewTqY!>0&S14Ri^z##M;2K)?-eTa>P~G3{+vaeCZ$3Cd zkbLL)_uq%#B-#z~-cRK}t48xS2aS`dr=sNJ2|0yPP79DtfQRE)noGxOAI zZGy0SQ2pJ&If3knauf>e(h_G-NeXWCQyHrvE#2VVUUcU8fwoA&bP&!e4uNkIWKmmr4vmg`UE?K} zmQd8jp^uLY+BA(f*j}Lz-sqE7PYS35(%_CpPBe>w`zVd_aO3!lTe{ z=-vOof2Yc8XezYZF&si554Y0?hH(O_U>COA_<{_0Mvhm*Rcza7_i;+n_xSm9g9A>yGw;Q}?Qmq$XE z&W17p$w z1D|G-g9q)R`bYv0B|%4}A5gUpQ(5o8h#BW$@IB3s5PU=z!SkaEZ!6HsU9V|;!kgJ) z@lX)^P=-0hY}I=s^K{nDy;^g$>xe?yP0LxJ^e{`cUmk$G7amqMzEdA*pv*?*dvhuZ znqIveJxZ4`S<`5L=m?2WyFVj;Nhy;rHIEdD-{@9MvnQJN!D0ep?3}bDAB24cNR0 zJjW_fXrsI_8KbqD5~Bx?${jgslxfJQT!b0@WJr<^3-GVtMt^fn1tkfN<`5q*5Ary! zx)<@zEB;i3XnXmRKNhlSKH%jo0WYLI0_LKB;-39-%qZxaU=9|AGxToZ6#nlM{`MdB z^3E;w5=MhErS>7-R!UGAkG%o^8f>4yXNYdm?*xzQ7sTP}QDz3i9IhT^5#$+!3`IJd zdibdWavrRAJ)L3d<3aGso2p1(PY;h6L1lihG&wUKyj}3btx|$3kI<4bult{9TG7NZ z-a~)Gte0;A$rB3oEyLJJE#rk;hTca+CMs9bgj zA#AYBM8r66i3#7I?I>$25L{EkAq&j>uM|JV<=+x_g}|J_R;EjfHiD%pFf=!vdNe|qAMOQwW@m$pRFnnCvb zO#1~U^@jPxF%^HMlQsh>%pRz6Z*mNjrk-l-+;G|9c^~@CX`L+aqWxvN{Q_s)YM*&w zV6nycZcx2Gq;q4B7`)>T1sAviL$GiAb_dpzctd;0<_-*6zujTKe8+lz@`S<#340q4 z1l52TH02at5DHnaZ_mD>$Ws#sG3@c(0sZ=YMfS`5dOmMrq5XovzPGKfjtw2``NFR8 z!wW{y?6Z+?3jKr1#D>rEeU^w)`~>e;xuFMwJzXirzQLp%;PK~+LF1KY9TBJ2#v4%% z{y5p-o_AMEpCr^bdV)QHzClwzl($d}GPSNKqPGnE@j6hPr(ol`w@uX9FBt93{%7$u zYy@Trcu4@?7aBC-avbQay3R&U_dV<2Pi#Q$huzf)rELPonNfcu_Ir_b#;bnRn_%t~ zuD@*OI{5&V_LSXLAQ({wsyDT7@D3^m>P&Oy9eB=7b+^eKuDkW9JFVQ> z_pzYZ`+capi7WAa%TMun;|f1ZK+Q>&{*T(tMxoPiHMP@tC8@yNX;ipQ!q(V@PK;N-&5@kRKToJ2w^aorcQ{DaBKz@vs816(8SJB%OM#9n)pu?zSkd z`DX1+y}(UHDb&NLJwLVJsFBAH7iFOo!_az>cHojk)CKuxW)^(}>$rpy1HBJ;4z%^< zA8z9!B07y-m+dovD5Ka>Ps7;IaGj2X%|&|}{FLi%cQ1tEb!)<)u3hYX`ys!MC zblmThp7XDln*0w*tNk|Mo4nc18^;yK`KiyOVV&c$h|f&H^nubP0FXqZlS zFpuJ#$_g*p^GrAx3vpRmIZ$3FB;3$Q;k4ZpcDwJ;TN^>!P)zbIG4bzUulo-8a#~*E zMb;Vvt#f#`vyoK3Ah~ZQ@xUTZ0ynVJ3|+l27k0)w`0{q-bq(nPdyiB_=zTw4pMmdc zlnloWejhWjg_e@E=>d(~Ik4t~E79y;Ing-aXNMh`-j|;_41N`7Hm2)?EcIS_z|Zn8 z!=%+=_Bt+e2$K=gb&@wa?ZK5Co2S*|_w7SCD-W#@ zofp?Be6gy0bp)QGiaY%qqjl_Q9Gn%1gGeDD1;zjM2=^cH;vtHU_KHU%5r3%54PNCR z8V&HO0_1Jw_eb=&`+DzP9ykT8`9|J^U0HQStT9dP@#g{&oY~Yv@VoMpf~zhe&N;ed z^z=koxVA1%xc20noqR2NL7ovnUXLpdDtr&05{s}0D=SNbT%#wbl=i5w>aNM< zhQ05vLEoBXXY<^sXBr1LzB{5JqM;6?(q0@7{Ga|qvh!XHT4Oa10erc61wx5Au+C0B z^dO!io&cY$FVPnpo5d6^1^&GGK~7!DbtQ0=;)z#4vURTby5h(9q-*$}PZ59#eO>uS zHxGQn1SkBH;eI^j)tlCLGcB|S@$4tP*E(yM3Wz&NUp~8A7!e7a1;&icX|Tm(DRZDb zGpImcG6;210DJa4ZJ!qO*P;CMy|90l&?`W{!rKmH1d5WXVvnWjrs+$fWd3UFqB!`( zYrZn`g&w~Vb);jR`U0Sfm^g3VYnC(tx{lvi#^2ZZP;G{Zz4XV=`!&Oz1_ z5-QyCKNDD6p~=)+my}98)aN*%xIkaD-OO{9oGp|=xOW>IsxMv=!A0)_sepPY#)_OC z(g6!hl76b;EkA;Cz`hT1rD4pq5aq&bfOM=d>H2_yG}JTQ`ZsbEbf8HY=DU%~%QA|DT*s_6MX5mqX6!%sS zDAOF4+F!fcuUVkH)x$>QWA6<*zLz&A!rJ#Ostx@m+ST7ozoloid>=}>!;#}#fwLr> zjr29*EFNbWzRNi4kFzx2=!*ML;vJ45z7;q#;w-_}h%*sq1ALcpro)*D8d>JC;ZjEV z%y<5@=uf^|-#1Uw`PJ!3qh6=~t=3Av^IKCxDV<8!yQV|>8T3sG?DwoJq+EfvOc^MJ zH%U(h*gqT)SnpQF5@?*|?q#V+Ik~Ia0UF(GIy!i|IWR;p9hxiea-@5|c%&X><}6l7 zbp^|@D;soiO%sm{DDf_;1I9nF{7plASDO;#h~bI89gl#EIa%5zKb7qZ9C?TOW3C;->*f397aa-SQ;%#y zy>O}4G`yWfrRaiuE*IqaT@JpT=b@L+YGfIkw)oL<^W4&vOBi(gdVeHW;c!ke6#XsX zJX})}l1owi*52#t-mqe6#VVHXayeF1EPePM7pqvYJR8S@tCyBny2{H|l`pPXxdQK; zxOCal(#Ogt(t|=68{d-xvHEBZ7wJ*$j&dg z%Z#{+(nrmUS5&MiU-4to-pr)Zibu;An^!F}mm$|x<>pm#`F}lHzNVtAe7re*@sE$s zSzT6EzH;S5s~>%It$9W7Ybm4KJl^|e^x1h#heO0+#9_kGA4fcnBphZOX*jI>yzIs0 zYqD3ZT05tbg-{K*`)Tb*5x(I}EYF1hGK3j8Dl(Y(TPqX)goDF*1@84hn1W+K@3DOZ z6C+0gTMEYm*-X5fLL8J|5#qLwW?}*EPr}g;=Wz%J;;rJyE>USUGFyP2SV(JI;keFW9fJBi9sdG?&aN>gc!LeA-1qj{gj8Q+J z7r=YHmSGHqU*o+dgy?lVh1CKRC`3j&gy!85Oi$OJip)TvsV|E_NW5;5uDAAMkqDjV zpofakU7gIL5!R&-Wk!U@J{rOLAZ&ej4C{-KMNVQd2rHI8#FmyWW!9x=_zbj-hPyYa zAdJJ;War>ka$ccWkF$)08Lr|8DBnKdYWHq9Cd5n>!PxjNfeg z=J~Znliz*j6Td7A_p#5*nOL$Ye10P}25b6aJn-A)Og!&m;%h6J zxEtY=N0^w6<5UH((r{eF@!V=AT9$^Ne*yNORBlUe*r)e?JJLB;Ke~h!+>?JVn>8=j z?3iJubMsG@tte%&=s7&vsch5?#&H}ka9TmAVSgNRUsW>k91hB#egGrV&IhlB&NL3X zmwqE$nVr6pW&il~xmjbz-f6Slynzq2u{m?^${9T+{0m9Nk9|eTP9< z$k~_vJd#!5pkEkkG88HX9qvXx9BZc`-ur94S+os^pMtxyFs5JVJ*P-5ftk(5>CJl7 P?xoN@lc?QvGxq-gD_v~G literal 0 HcmV?d00001 diff --git a/boards/qiotek/zealoth743/firmware.prototype b/boards/qiotek/zealoth743/firmware.prototype new file mode 100644 index 0000000000..77470ef536 --- /dev/null +++ b/boards/qiotek/zealoth743/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1009, + "magic": "PX4FWv1", + "description": "Firmware for the CUAV Nora board", + "image": "", + "build_time": 0, + "summary": "Nora", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/qiotek/zealoth743/init/rc.board_defaults b/boards/qiotek/zealoth743/init/rc.board_defaults new file mode 100644 index 0000000000..bbc9316544 --- /dev/null +++ b/boards/qiotek/zealoth743/init/rc.board_defaults @@ -0,0 +1,22 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# Enables the 2nd bank of mixers +set AUX_BANK2 yes + +param set-default BAT1_V_DIV 18 +param set-default BAT2_V_DIV 18 + +param set-default BAT1_A_PER_V 24 +param set-default BAT2_A_PER_V 24 + +# Enable IMU thermal control +param set-default SENS_EN_THERMAL 1 + +# Set Camera trigger pins to 13/14 +param set-default TRIG_PINS_EX 12288 + +rgbled_pwm start +safety_button start diff --git a/boards/qiotek/zealoth743/init/rc.board_sensors b/boards/qiotek/zealoth743/init/rc.board_sensors new file mode 100644 index 0000000000..b6dcb5b0cb --- /dev/null +++ b/boards/qiotek/zealoth743/init/rc.board_sensors @@ -0,0 +1,29 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ +board_adc start + +# SPI1 +icm20689 -s -b 1 -R 2 start + +# SPI2 +rm3100 -s -b 2 start + +# SPI4 +bmi088 -s -b 4 -A -R 2 start +if ! bmi088 -s -b 4 -G -R 2 start +then + icm42688p -R 2 -s start +fi +ms5611 -s -b 4 start + +# SPI6 +if ! icm20649 -s -b 6 -R 2 start +then + icm20689 -s -b 6 -R 2 start +fi +ms5611 -s -b 6 start + +# External compass on GPS1/I2C1: standard CUAV GPS/compass puck (with lights, safety button, and buzzer) +ist8310 -X -b 1 -R 10 start diff --git a/boards/qiotek/zealoth743/nuttx-config/bootloader/defconfig b/boards/qiotek/zealoth743/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..9ea14fb7c9 --- /dev/null +++ b/boards/qiotek/zealoth743/nuttx-config/bootloader/defconfig @@ -0,0 +1,93 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cuav/nora/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743XI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004c +CONFIG_CDCACM_PRODUCTSTR="PX4 BL CUAV Nora" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="CUAV" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_PTHREAD=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_LIB_BOARDCTL=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_USART6=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="bootloader_main" diff --git a/boards/qiotek/zealoth743/nuttx-config/include/board.h b/boards/qiotek/zealoth743/nuttx-config/include/board.h new file mode 100644 index 0000000000..e59d9c16fa --- /dev/null +++ b/boards/qiotek/zealoth743/nuttx-config/include/board.h @@ -0,0 +1,268 @@ +/************************************************************************************ + * nuttx-config/include/board.h + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#pragma once + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/* Clocking *************************************************************************/ +/* The board provides the following clock sources: + * + * X1: 8 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 64 MHz RC factory-trimmed + * HSE: 8 MHz crystal for HSE + */ +#define STM32_BOARD_XTAL 8000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 0 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_4_8_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * Note: look at Table 54 in ST Manual + */ +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */ +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */ +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */ +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */ +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */ +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */ +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */ +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states */ +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* UART/USART */ +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB15 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB14 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ + +#define GPIO_UART3_RX GPIO_UART3_RX_5 /* PD9 */ +#define GPIO_UART3_TX GPIO_UART3_TX_5 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PB8 */ +#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PB9 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + +/* CAN */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI */ +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_3) /* PA5 */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PA7 */ + +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PD3 */ +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PC2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PC3 */ + +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_6) /* PB3 */ +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_3 /* PB4 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */ + +/* I2C */ +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB6 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB7 */ + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PB11 */ diff --git a/boards/qiotek/zealoth743/nuttx-config/include/board_dma_map.h b/boards/qiotek/zealoth743/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..428ef3f0f9 --- /dev/null +++ b/boards/qiotek/zealoth743/nuttx-config/include/board_dma_map.h @@ -0,0 +1,49 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + +#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */ +#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */ + +#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0 /* DMA1:83 */ +#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0 /* DMA1:84 */ + + +// DMAMUX2 (BDMA) +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */ diff --git a/boards/qiotek/zealoth743/nuttx-config/nsh/defconfig b/boards/qiotek/zealoth743/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..367d77c1ee --- /dev/null +++ b/boards/qiotek/zealoth743/nuttx-config/nsh/defconfig @@ -0,0 +1,233 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_TIME is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cuav/nora/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743XI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004c +CONFIG_CDCACM_PRODUCTSTR="PX4 CUAV Nora" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="CUAV" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +CONFIG_NSH_DISABLE_TELNETD=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_NNESTPRIO=8 +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI_DMA=y +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM15=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=n +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y diff --git a/boards/qiotek/zealoth743/nuttx-config/scripts/bootloader_script.ld b/boards/qiotek/zealoth743/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..c2eba58f26 --- /dev/null +++ b/boards/qiotek/zealoth743/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,223 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The board uses an STM32H743XIH6 and has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + DTCM1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > AXI_SRAM AT > FLASH + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + .ramfunc : { + _sramfuncs = .; + *(.ramfunc .ramfunc.*) + . = ALIGN(4); + _eramfuncs = .; + } > ITCM_RAM AT > FLASH + + _framfuncs = LOADADDR(.ramfunc); +} diff --git a/boards/qiotek/zealoth743/nuttx-config/scripts/script.ld b/boards/qiotek/zealoth743/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..025930da82 --- /dev/null +++ b/boards/qiotek/zealoth743/nuttx-config/scripts/script.ld @@ -0,0 +1,222 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The board uses an STM32H743XIH6 and has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > AXI_SRAM AT > FLASH + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/qiotek/zealoth743/src/CMakeLists.txt b/boards/qiotek/zealoth743/src/CMakeLists.txt new file mode 100644 index 0000000000..2c040010bd --- /dev/null +++ b/boards/qiotek/zealoth743/src/CMakeLists.txt @@ -0,0 +1,66 @@ +############################################################################ +# +# Copyright (c) 2020 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/qiotek/zealoth743/src/board_config.h b/boards/qiotek/zealoth743/src/board_config.h new file mode 100644 index 0000000000..2b552007e4 --- /dev/null +++ b/boards/qiotek/zealoth743/src/board_config.h @@ -0,0 +1,228 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +#include +#include +#include +#include + +/* LEDs */ +#define GPIO_nLED_RED /* PE2 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#define GPIO_nLED_GREEN /* PE1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN1) +#define GPIO_nLED_BLUE /* PE0 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN0) + +#define BOARD_HAS_LED_PWM 1 + +/* ADC channels */ +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA1 */ GPIO_ADC1_INP17, \ + /* PC0 */ GPIO_ADC12_INP14, \ // TODO + /* PC1 */ GPIO_ADC1_INP2, \ // TODO + /* PC5 */ GPIO_ADC12_INP4, \ // TODO + /* PB1 */ GPIO_ADC1_INP6, \ // TODO + /* PA4 */ GPIO_ADC12_INP8, \ // TODO + +/* Define Channel numbers must match above GPIO pins */ +#define ADC_BATTERY1_VOLTAGE_CHANNEL 16 /* PA0 */ +#define ADC_BATTERY1_CURRENT_CHANNEL 17 /* PA1 */ +#define ADC_BATTERY2_VOLTAGE_CHANNEL 14 /* PC0 */ // TODO +#define ADC_BATTERY2_CURRENT_CHANNEL 2 /* PC1 */ // TODO +#define ADC1_6V6_IN_CHANNEL 4 /* PC5 */ // SPARE1_ADC1: ADC6.6 // TODO +#define ADC_RSSI_IN_CHANNEL 6 /* PB1 */ // TODO +#define ADC_SCALED_V5_CHANNEL 8 /* PA4 */ // VDD_5V_SENS: Motherboard 5V voltage detection // TODO +// TODO: PC4 FMU_SERVORAIL_VCC_SENS + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY1_CURRENT_CHANNEL) | \ + (1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY2_CURRENT_CHANNEL) | \ + (1 << ADC1_6V6_IN_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL) | \ + (1 << ADC_SCALED_V5_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) + +/* CAN Silence Silent mode control */ +#define GPIO_CAN1_SILENT_S0 /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN11) +#define GPIO_CAN2_SILENT_S1 /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN10) + +/* HEATER */ +#define GPIO_HEATER_OUTPUT /* PE16 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN15) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PWM */ +#define DIRECT_PWM_OUTPUT_CHANNELS 14 +#define BOARD_NUM_IO_TIMERS 4 + +/* Power supply control and monitoring GPIOs */ +#define BOARD_NUMBER_BRICKS 2 + +#define GPIO_nPOWER_IN_ADC /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_CAN /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN0) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_CAN /* Brick 1 is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_ADC /* Brick 2 is Chosen */ +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB is Chosen */ + +#define GPIO_VDD_5V_HIPOWER_EN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11) +#define GPIO_nVDD_5V_PERIPH_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_RC_EN /* PG5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5) +#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7) + +#define GPIO_VDD_5V_HIPOWER_OC /* PJ3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN3) +#define GPIO_nVDD_5V_PERIPH_OC /* PJ4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN4) + +/* Power switch controls ******************************************************/ +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, (on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_EN, (on_true)) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) + +#define SPEKTRUM_POWER(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_EN, (on_true)) +#define READ_SPEKTRUM_POWER() px4_arch_gpioread(GPIO_VDD_5V_RC_EN) + +/* Tone alarm output */ +#define TONE_ALARM_TIMER 15 /* timer 15 */ +#define TONE_ALARM_CHANNEL 1 /* PE5 TIM15_CH1 */ + +#define GPIO_TONE_ALARM_IDLE /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5) // ALARM +#define GPIO_TONE_ALARM GPIO_TIM15_CH1OUT_2 + +/* USB + * OTG FS: PA9 OTG_FS_VBUS VBUS sensing + * HS USB EN: PH15 + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) +#define GPIO_HS_USB_EN /* PH15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN15) + +/* High-resolution timer */ +#define HRT_TIMER 3 /* use timer3 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + + +#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PC8 T3C1 */ GPIO_TIM3_CH1IN_2 +#define RC_SERIAL_PORT "/dev/ttyS5" +#define RC_SERIAL_SINGLEWIRE + +/** + * GPIO PPM_IN on PB4 T3C1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART8 PE0 + * Inversion is possible in the UART and can drive GPIO_PPM_IN as an output + */ +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + + +/* Safety Switch is only on FMU */ +#define FMU_LED_AMBER /* PC14 */ (GPIO_OUTPUT|GPIO_PULLDOWN|GPIO_PORTC|GPIO_PIN13) // FMU_LED_AMBER +#define GPIO_BTN_SAFETY /* PE4 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN4) // SAFETY_SW + +#define GPIO_LED_SAFETY FMU_LED_AMBER + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) +#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_OC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_HW_REV_DRIVE, \ + GPIO_HW_VER_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_CAN2_SILENT_S1, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_CAN, \ + GPIO_nPOWER_IN_ADC, \ + GPIO_nPOWER_IN_C, \ + GPIO_nVDD_5V_PERIPH_EN, \ + GPIO_nVDD_5V_PERIPH_OC, \ + GPIO_VDD_5V_HIPOWER_EN, \ + GPIO_VDD_5V_HIPOWER_OC, \ + GPIO_VDD_5V_RC_EN, \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \ + PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_OTGFS_VBUS, \ + PX4_GPIO_PIN_OFF(GPIO_HS_USB_EN), \ + GPIO_RSSI_IN, \ + FMU_LED_AMBER, \ + GPIO_BTN_SAFETY, \ + } + +__BEGIN_DECLS +#ifndef __ASSEMBLY__ + +extern void stm32_spiinitialize(void); +extern void board_peripheral_reset(int ms); + +#include +#endif /* __ASSEMBLY__ */ +__END_DECLS diff --git a/boards/qiotek/zealoth743/src/bootloader_main.c b/boards/qiotek/zealoth743/src/bootloader_main.c new file mode 100644 index 0000000000..bb6b4dc23a --- /dev/null +++ b/boards/qiotek/zealoth743/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2020, 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_configgpio(GPIO_OTGFS_VBUS); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/qiotek/zealoth743/src/hw_config.h b/boards/qiotek/zealoth743/src/hw_config.h new file mode 100644 index 0000000000..4a1fca5447 --- /dev/null +++ b/boards/qiotek/zealoth743/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS4,57600" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1009 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/qiotek/zealoth743/src/i2c.cpp b/boards/qiotek/zealoth743/src/i2c.cpp new file mode 100644 index 0000000000..c7a92317f8 --- /dev/null +++ b/boards/qiotek/zealoth743/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * 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), +}; diff --git a/boards/qiotek/zealoth743/src/init.c b/boards/qiotek/zealoth743/src/init.c new file mode 100644 index 0000000000..d4c262b76a --- /dev/null +++ b/boards/qiotek/zealoth743/src/init.c @@ -0,0 +1,219 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + + bool last = READ_SPEKTRUM_POWER(); + /* Keep Spektum on to discharge rail*/ + SPEKTRUM_POWER(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + SPEKTRUM_POWER(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_PERIPH_EN(true); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + board_control_spi_sensors_power_configgpio(); +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Power on Interfaces */ + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + board_control_spi_sensors_power(true, 0xffff); + SPEKTRUM_POWER(true); + + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure SPI interfaces (after we determined the HW version) */ + stm32_spiinitialize(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + +#ifdef CONFIG_MMCSD + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0); + } + + if (mmcsd_slotinitialize(0, sdio_dev) != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n"); + } + + /* Assume that the SD card is inserted. What choice do we have? */ + sdio_mediachange(sdio_dev, true); +#endif /* CONFIG_MMCSD */ + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + return OK; +} diff --git a/boards/qiotek/zealoth743/src/led.c b/boards/qiotek/zealoth743/src/led.c new file mode 100644 index 0000000000..79792ca1a2 --- /dev/null +++ b/boards/qiotek/zealoth743/src/led.c @@ -0,0 +1,111 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + FMU_LED_AMBER, // Indexed by LED_SAFETY (defaulted to an output) +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/qiotek/zealoth743/src/spi.cpp b/boards/qiotek/zealoth743/src/spi.cpp new file mode 100644 index 0000000000..ebdd4a37e1 --- /dev/null +++ b/boards/qiotek/zealoth743/src/spi.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortB, GPIO::Pin2}), // TODO: IMU1 + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortE, GPIO::Pin10}), // TODO: IMU2 + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortE, GPIO::Pin12}), // TODO: IMU3 + initSPIDevice(DRV_BARO_DEVTYPE_DPS310, SPI::CS{GPIO::PortE, GPIO::Pin3}), // TODO: DPS280? + initSPIDevice(DRV_BARO_DEVTYPE_DPS310, SPI::CS{GPIO::PortD, GPIO::Pin7}), // TODO: DPS280? + initSPIDevice(UNUSED, SPI::CS{GPIO::PortA, GPIO::Pin8}), // TODO: AT7456? + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortA, GPIO::Pin10}), + initSPIDevice(UNUSED, SPI::CS{GPIO::PortC, GPIO::Pin10}), // TODO + }), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ADIS16470, SPI::CS{GPIO::PortA, GPIO::Pin15}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/qiotek/zealoth743/src/timer_config.cpp b/boards/qiotek/zealoth743/src/timer_config.cpp new file mode 100644 index 0000000000..bc83b5892d --- /dev/null +++ b/boards/qiotek/zealoth743/src/timer_config.cpp @@ -0,0 +1,82 @@ +/**************************************************************************** + * + * Copyright (C) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer3, DMA{DMA::Index1}), + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortC, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); + +constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = { + initIOTimer(Timer::Timer8), +}; + +#define CCER_C1_NUM_BITS 4 +#define POLARITY(c) (GTIM_CCER_CC1P << (((c)-1) * CCER_C1_NUM_BITS)) +#define DRIVE_TYPE(p) ((p)|GPIO_OPENDRAIN|GPIO_PULLUP) + +static inline constexpr timer_io_channels_t initIOTimerChannelLED(const io_timers_t io_timers_conf[MAX_LED_TIMERS], + Timer::TimerChannel timer, GPIO::GPIOPin pin, int ui_polarity) +{ + timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, timer, pin); + ret.gpio_out = DRIVE_TYPE(ret.gpio_out); + ret.masks = POLARITY(ui_polarity); + return ret; +} + +constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { + initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}, 1), + initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}, 2), + initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel3}, {GPIO::PortI, GPIO::Pin7}, 3), +}; diff --git a/boards/qiotek/zealoth743/src/usb.c b/boards/qiotek/zealoth743/src/usb.c new file mode 100644 index 0000000000..3d86aca280 --- /dev/null +++ b/boards/qiotek/zealoth743/src/usb.c @@ -0,0 +1,59 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +}