From 6981a70859f8fff5addaa72d510384701d78de6e Mon Sep 17 00:00:00 2001 From: Kirill Shilov Date: Sun, 24 Apr 2022 18:57:42 +0100 Subject: [PATCH] boards: new Sky-Drones AIRLink board support --- .ci/Jenkinsfile-compile | 1 + .github/workflows/compile_nuttx.yml | 1 + .../smartap-airlink/default.px4board | 109 ++++ .../extras/px4_io-v2_default.bin | Bin 0 -> 39952 bytes .../sky-drones_smartap-airlink_bootlader.bin | Bin 0 -> 10480 bytes .../smartap-airlink/firmware.prototype | 13 + .../smartap-airlink/init/rc.board_defaults | 31 ++ .../smartap-airlink/init/rc.board_sensors | 34 ++ .../smartap-airlink/nuttx-config/Kconfig | 17 + .../nuttx-config/include/board.h | 503 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 100 ++++ .../nuttx-config/nsh/defconfig | 289 ++++++++++ .../nuttx-config/scripts/script.ld | 190 +++++++ .../smartap-airlink/src/CMakeLists.txt | 58 ++ .../smartap-airlink/src/board_config.h | 406 ++++++++++++++ boards/sky-drones/smartap-airlink/src/can.c | 123 +++++ boards/sky-drones/smartap-airlink/src/i2c.cpp | 41 ++ .../sky-drones/smartap-airlink/src/init.cpp | 269 ++++++++++ boards/sky-drones/smartap-airlink/src/led.c | 232 ++++++++ .../sky-drones/smartap-airlink/src/manifest.c | 138 +++++ boards/sky-drones/smartap-airlink/src/mtd.cpp | 104 ++++ boards/sky-drones/smartap-airlink/src/sdio.c | 177 ++++++ boards/sky-drones/smartap-airlink/src/spi.cpp | 60 +++ .../smartap-airlink/src/timer_config.cpp | 78 +++ boards/sky-drones/smartap-airlink/src/usb.c | 105 ++++ 25 files changed, 3079 insertions(+) create mode 100644 boards/sky-drones/smartap-airlink/default.px4board create mode 100755 boards/sky-drones/smartap-airlink/extras/px4_io-v2_default.bin create mode 100755 boards/sky-drones/smartap-airlink/extras/sky-drones_smartap-airlink_bootlader.bin create mode 100644 boards/sky-drones/smartap-airlink/firmware.prototype create mode 100644 boards/sky-drones/smartap-airlink/init/rc.board_defaults create mode 100644 boards/sky-drones/smartap-airlink/init/rc.board_sensors create mode 100644 boards/sky-drones/smartap-airlink/nuttx-config/Kconfig create mode 100644 boards/sky-drones/smartap-airlink/nuttx-config/include/board.h create mode 100644 boards/sky-drones/smartap-airlink/nuttx-config/include/board_dma_map.h create mode 100644 boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig create mode 100644 boards/sky-drones/smartap-airlink/nuttx-config/scripts/script.ld create mode 100644 boards/sky-drones/smartap-airlink/src/CMakeLists.txt create mode 100644 boards/sky-drones/smartap-airlink/src/board_config.h create mode 100644 boards/sky-drones/smartap-airlink/src/can.c create mode 100644 boards/sky-drones/smartap-airlink/src/i2c.cpp create mode 100644 boards/sky-drones/smartap-airlink/src/init.cpp create mode 100644 boards/sky-drones/smartap-airlink/src/led.c create mode 100644 boards/sky-drones/smartap-airlink/src/manifest.c create mode 100644 boards/sky-drones/smartap-airlink/src/mtd.cpp create mode 100644 boards/sky-drones/smartap-airlink/src/sdio.c create mode 100644 boards/sky-drones/smartap-airlink/src/spi.cpp create mode 100644 boards/sky-drones/smartap-airlink/src/timer_config.cpp create mode 100644 boards/sky-drones/smartap-airlink/src/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 36bb8bea67..a2f78f2351 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -104,6 +104,7 @@ pipeline { "px4_fmu-v6u_default", "px4_fmu-v6x_default", "px4_io-v2_default", + "sky-drones_smartap-airlink_default", "spracing_h7extreme_default", "uvify_core_default" ], diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml index 5d6c74691b..177f10e83b 100644 --- a/.github/workflows/compile_nuttx.yml +++ b/.github/workflows/compile_nuttx.yml @@ -61,6 +61,7 @@ jobs: px4_fmu-v5x, px4_fmu-v6u, px4_fmu-v6x, + sky-drones_smartap-airlink, spracing_h7extreme, uvify_core ] diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board new file mode 100644 index 0000000000..125123fad5 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -0,0 +1,109 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_PPB="/dev/ttyS3" +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_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=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_PWM_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PWM_OUT_SIM=y +CONFIG_DRIVERS_PX4IO=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_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_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL_L1=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MIXER=y +CONFIG_SYSTEMCMDS_MOTOR_TEST=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_PWM=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_REFLECT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y +CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/sky-drones/smartap-airlink/extras/px4_io-v2_default.bin b/boards/sky-drones/smartap-airlink/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000000000000000000000000000000000..25a00e2357d781ece9c0d41447c3f4a52c6d19f6 GIT binary patch literal 39952 zcmeFZiGNhp{Xcx}GFvi`$pT~pW(hFKuml1c#buaDZk7o~iTxG<+lxVa5j0WM#x61t ztRuk|janowXlz}eH8T)P&^S@Fb*b$POA7=_6zi2l>m3Npoow^G&rDGI`#!JddH#S0 zUN`s7J=^De&gXpgb1Nqj^P+U3KbrUdU;kfmpzkEgyiuaeQi)O?Bg#`Mv7~y8)vd0S z!}M;fYH{fg6Xn}st#V+5QC5$*RX*=qd6~+m;wkl8nFP19#B7{E%!ClL_cfw_48NnD zq+qUR-VOQUDlyA8w{mXPyy_B>7mZ@3G-s(>VYp0jwr9F@t#hh4Nt&T-xqrr>chMyJ zJm{S{A!wwHo(lm8yfr-=I5}Ye+6PO5Z{9Qz^C4G&bN=1J zv{`Qw-H=wb_3QNqQ#i%Qx%&;=UZ=ZX&;1p(emwN+^9#Bv_`IXE9Wi%*r8Engw4x1$(CmyypANdTwf&~dv?KazPSJ78RGXO;q6aQ3XtHEk zFh9Z#5yf{S#Q|;qzv>s$Iy)uCM(deeS;1_9m{A)StNa&^&9)@hEFS$L{zYI5R^h+jFY&Vthoxm}IrPK=)0ys6FR{d< zpI%mb^ZL5Gvl^D`58wTnw0BrJzudqn(>bQ(GjXNf-A^)24b7ruu%qq?b+w5p%nyS` z>z`0>BL+Jg(%adv!S5dQ)}=RmBBnPyq1KbswYEWLogQyVUFzzL2EaV%+)xLI*+P8~ zb?Z;d&Fga;Zj|<_KQcS}SyzfktUZBt{A#Q)b$Zu-Kd%mTRq<7Rw_;}E(MP_6**3WS z9t*HBh<@@KvZbE$PE%t=^ZI6WOX8l_a0^!NQdtk)m3Hz%qTh#;_@e#Zf_}Zsqk(vI zMcgbf%4YSOz{9{`X}1mU4ZOh^k1mZ5%BIdO>yM~jLX^J`9Z`M7JrOf$b{RuQ)NSVJ zj?gMD!muepVtZfpnQ;}Hx`}y2F74!mHpzcs)5crZnuI;;uM7Dv?AWLcInObf&$x0! z4N5k_NDc4lZe3g7U^oh_g2HEvl`DFUt>Mb%X5jrfnG{_WdQx3o zyxY$>Y6rdd8iTciWCO8fx}Q|*&7>$R=(G}RCiqD)*DS8Sn=qW>ykA@|6T8 zo>V1ZV#YAB(x-Hx`zw=^Q5p^qQrh|OdTmva@D$!N${jv@feaD$Y5&57h3{PC9B9h;lK`*!F=E(zQDJ-khQ367TooJ$PY= zIQqiGT-u$fOyu%|brP}3m#xrP?9vKl=Vk{Pv#I+DbxW}cqq_Yj%&0$Z_L~zh6Xo3? zR?1S^sS&oUHw#--(G-ua9^1V>t2(ct)s-J&FEqO7{iO@{;jRe-)AJ`*5-U;u7PDek z*+Abm?Bc_s*btBI8Qs;;{Z%Q}>XmNH(85=qm2qFfRsI_?iBysV-=_SV(o;P8Ui?f$ zoj*xeF9K>xU+ZI(ioBqpQq-|k+Zr@NtLy4tFToTgI`-&k_z}O}%{Q>laD*wk#S9kp=UlNK-9#ajV`01l10<(~t{cV`ce$8ztvYC0^}w?h3Ic%+RJ|ZW$Y3krm#`CGQoQ$M6`?n(99oAnazeL znB&opNBY2d{xZ_7YE2wUvN12V0~DE4tpIP! ztZwWiwk+YMCZ9_iVoG!lHezC<;aVkLGL3ohR(^mpZ6#?IxAeI4QoE^Aq4O5;VQG%P z{nq!SHgeqgQQ%c7`7mY&;6#rzQfrJiFjivOl~0u4#)x&kAT}|ISEVb_8D|!WO~7wV zH;0dy`2KKXH*I%oF41c}rcQ2vWMK})jN*zB`<@_nGxlGyZ~As=S8->#v_~pX7=Djf zCRtW5k*Zg_q{HG8iEG=Mn6Gs(?pn!Pl}2`@G1J{57I*iYWiysYKFJB`<<;tr5Jz^< zXwwH%!1G$DjK=SYwu^E+dVA0<9h0a8`Cfi-lC7U%QrxU~CO~x*z(a~V4IV>f4md}y zpsz73efPZ1@{EfO>!3RocXOguWJ-#}3-b1FNZ$@zyKp^=>q%VSp4WJ%DSR3m`u4nG z(__M&0vj>27_WKG*^%0{!g`@V(Xmf~kM*e*!RIoBNMttS|4KdeaTBgsB zzqA))aMO9cZ_{~$kHUtzkTkog({##IT9(cYY~i?w=;ki0cBf)rf<_a%jY*_fo#5f^ z&=bLvyd{}{RRcK;{#2sM+QgIBc3w`ib79^?+kPX1E{e}!Zxvt;rasbF+DR!Tr#h!5 zQ>+tnJUP|v7x}t_DnF-I@h&*1X3epR2i5#Jc~VvtQ_@SA#ZwNE85y1;A)_kQJXIvh z1MwokRK=Nza!=fbwc7}p)91E{NT>17zKTZb)v zOQ?rr%v-mkg4koB`t^kZ<-Lv0wmY*c=A2b)%Ue2P(~9Q=m_@wc6CM|KyN(6P3{X%C zbn?{pmb}1jx&zGhE!I2p0&@ba%6V^Z?*2;sO;-d=4SOj4k*%QoWXkSAXTaOAj5W?q19l0uHibIwLws6pmsC0BgfQ}On6ofB_n?6%`|94F`MDevn_Ni=#K9U7| zR*xkxXb)ce*&Dzi|Da5NCwp*WwCxpl0i!qa^lu7(C-AB)X_jtXtBIKOPGF-5_{`~@ z+r(TkS&3`sg_yaH1jNZbH_#Lhtm|60-Y(=xSixz!6SQ~Q?gn5HINU_b+7e~!)^jK9 z!b&`UEw8*Y)o;g|uUpSpP`-9Y1#LIC@iRa%h5wfv?MxF$q()03t2FGn-k0zZ@UQHvD5vrBJe(D7~ZgE&F2A%y|K(WG7u? z+e!O8?LP(o+1E*mswWhZzb zg|Aui3TeV*;nuZ`a{pM9AJC0krn&*Get)?woYaaICOC-l2vLrWY!ZmQKdgylr`(8f z$42;RO7Ag@RwXnmPCca)y5s%Ahv&W7lwah87Yd8}c1u%KChwSzJ366I6VBCXj!;YG z)zQDoDTT3crc#i`g(iT8;?d_vQ!I*ndHodBPdVZeXz2^1{4`UqArikTgqDMemP|Os z@~!L=lI?$u8W&Ia%b7#JA29HDw(K6qEgwo!DTR(g{@KWriCywZlSVKK4*w^T8>{|_ zsIj$(RF?uRk$6-YNj?|gxqtlGgy%0th!tz6OBYH3)v3gp4uQwU>LL;zM z1Xj@w5lb=d?2rxfz)CHt9qhfAfrh)Siv-s{PxVwD+za~9SbNiAKc(<2(%wkzG@`V; zP5lGBz@z*JWA)?Z8Ki!^{O2fd?7XyJ>euICCz>KTX-;L6*LhA?@;tcSn-^Rgbtm4u zuyx}PVa-m;eBQM#)Yx5uX9LP(lpAbHQs(#cc=d_)mfIi?G6HS6%;GfYQJ3miA3L)x zNwX;@&up_kmaOw}fbwPsBwARuKGwHwU#zG&BR~Qfxr+RK+m~AE$Jc~AS>N&!`tOrp zY7yyfP1Kg<+gf&^1_>nIWkNMSjB@XR(%B)&)=v^~ts;g8j~n1%M{c=Yc0 z#lWvHeo#)zJJ&hWJ@M$`cZhv!nA-2pyHbFKO&goT_xl}Ey|_+l7YC#>;?Lzp{(8wF zwoB{8Gtz*#0lNe`0PIs95-bCDMhaGut_M*xBTRxah(Z!i1$Z|+3=TyYOLDCS-=Zs_ z0q26Ytt|$nJw0q|VjSAz%wk(3{r&QALVLH=ueUU|t)(*40q+%m1bcTiB;GXZvBVtKULRmy+fng`>#NY2 zZJ$HO2;J-moY_LDg;|vBi@D+$cIWveI`Gcz!c<_*q4Lu*dY53oF|UK);gKk z(Sv9C+pS7k!cTi*6H$s`_aw(Nb?Ryus~M{pkERaSUW{+3_YzyXH@Q+Z`xk-_mO`hp zji%ISgnco#xY@LPjhu%%)n*j=3gFW#(mc z5o>PaIeA{uPzd^?V^G$2Qrq%haq7>6<{9K)Ci-hIF0oO$o+(Zi*d|{GDJlJP;5ygHn@ki;d z;r}6XLQYe*kSj1H^ZoM*)v!t6nwSOi97CbT3bm8N&d6<=SELWksK?m8u1q*jZ%0#o~6mVMWFX;Pmk4}cw&{o7-!r4fZ(a9{@^TMqP6XAF85poX>jl? zDcG~=1GNX(_}SPJk0eYLSsU|ONh71Y9D`lOFv^?5yzQDAn`o05$Bn1VQV)D}@4=e~ z%KOC>;R?`+S;~>NyUI^mG2;nho>W-*thaC@-Td;ailsZD~l3>)j4 zVaB>!%Du<#$@g-$l15fJADih(^&^%uG6Q!;xiwaRJGJj@iT8DJMzIa?wv5UWXc@{d ztGt6~&kj|C)|AeOvP)%@U&Kaao3xU=A}>)FH0DUmzLe^_M`O<7)_(06mb*6tiGF1=OO}oFZoPnoAyfVl%JNz$Ub9VU)+zeK9j3b|vI= z{fF*3GLYz#N?j^5!f|fuP>AY1@#rUUewy|K=ulnb;u97)JVNl+bAqX}axcc;lC%md zF2?Vn5Nw6tH>tTcC|e047(ONeO%gi8Nkg?sD)zJMce?b@;<+^x*U9?CEXzbndd@$W zDSciVUxV?lzcl_rvp_X2N?Y&&#=oa7hcA~m9C7&a_=!i8+DJS)Ii8UBv(KNh3(Pg~ z=*#hfK)*cO`yW}?Df#u)#L_W*?mRo339l=3fDOyt%ytQU`|A-dVbg=(xYEd+v+*Uo z@V?mxeSJFO9*1KZ;h5jpwoA?TvaP9Y7J+F^XY^LT zoJHZksl-WbpV!gnvt@hWKe!lpX%ponY}<2csoA!g!<{$PuWoN)5lOZw2f0jldov#? zV=WJ?et1rHoMY#Z^7I$YOj{`^Vxwz_jU~2mX_MPoUXt6p-OJtESG~9&sG=o zF$=y#AM<1UUvEx{AyeKZ>7zS;4Ks zPQfeOC`>}{PmBrqi{6?ounV;VTNrAI4#Zy}@ch`zLS#T^=uye`8&U6}F-m} z-Zl9Uv+!+~5^hkmM3y}&UyI1VbiKel&L}lwn+4_>Gw6*;8H-*!c5~U^LFX&TVM^^J z1fKX!g7+r)MZ(`nl#cJBlkhZ}F>clb@XNz$k9nDDHdS@4TH7|x7xm$EVOIrF@>HgH zm+RXwV^(DboQhFCA42>j!EZI5Y^l`W{1E40!yPdr{D=(-i@%gt@`ApT_k0n^mIz`g zL|KC98e&Idw2bn+<$kYZ1}{FW?t&-euZV3XwbZ{L-bJHbqM0biiIk4$5Oh`&lyb4?%PEUA^OVpcWNQp1deQT{n*7g*d6 zCp<)@;49=U<`kn$06ddPX*Z3-(0L`>M?lxf`Fw+zBeCTOnrdw&Q?k_Y9`qYFqG#3c zSoAkso$7Ni*w*~niFGD`{=l|N=OT}bBZw8qlLtn zD#fE?!)g9?>lceJQ@EOw(uYMvFH0yoCjQRAq%x}I-;uG_# zwfFh04{mj7!(1ebDel5vR7O?4&ny&3@MbGa?2^4&3R%wmd?nRswv4YSINe_LQsj+w zXsH)syo|3>WX5qmoTQqvcaG?Y`LDR>USJ9+#EjA$Gj}ly&9f5`G+?KUE_m)2yni;`Tnb;lefS&1JZB6mi1^bM#zd_bReM(!`eBr3)$A@> zuXN}f?4Nez6Hv=*f?#Okg_yq#JEAzb0}r9pmt6HpRg|_ijI=+bb?C$Y zCx+ya9}oG?Co+@f=|c=629w}Lq22@VIqh+|{UMFxVwi^(NtE+yM7~59-B%Jll~BBZ zn1LQNz%i{PaTmUVPWo_>wy_BFKrGGT*M{Bv!@$n2;_3Mj;Tb<4Q zsoYfO!~LmfLzMdXkB7Dn(O3y$$Ya#^^L6Y^@KwO+PJ?bm>{oMpNj_q!n-*l+=;+dD+@ zo0^Cqe+Dl>Ji2VGy#*Nu_3h0`UnG2CC{6Cp{QU*+J7gb7@_VAZK1OU-cr&xHlZr;I z0x&XPeUX<~nJp}E{mF2Wk6_mlc*6?pp28boS(n*8qM6=jdH#&Q^l7Gt{w0ca zL?cxCNkr7mzTXaAH+vD4$8Wfz;U4UY%n>S+*;&~)kVuba*8OH$Vv&1}s*^kG)R;`^qZuc=eC^xq}Ncs6^V+GPVdGkZsq7-;K<5uLMneVfDk&i>H z>>Wh8_N~SWN^@60{!D;IpHDgX_-@pJLm{srUg~7FW9LOX{LHJ!j~k`BO+2a}o#ST( zL|U$Qh;{IfY9EY8^G9ivr&vhrpXL&&eGT>VmxPGrxXKq#s{|GH^<nJea-a3jAL}KJUQm` z{5f>9x(X1~1A-n|o7nqz#l8eJr)a;$UrzgVLN;9wJBiv#Z(R-j;p3f)OFJjPo8^QD zLr}kvvi!DR>~?XGX5gQY6$KLfdBg<&Uo__QPpBlyi=!P~l%iAd+(v10ToxgRMQI&P z(wDs}8!O8X!+&Pu?l*N`T0h9PU;ejjL!^4V4J^?A2if+I1DE=sGR6q|ZbyPQEC_Ag zOA6;*7Bg~7)H}0AonCdfI8pjQHF}wa)4J&1H;vBjD;8k=*&dfxW-~|ArTJa$uB?;k zQejtC)fc&6%O)X3P-LIPl_j4Fg^AUe$Ec}~YAzXlk4sOx+6Nf!Ex*h($`a71<&7 zv!P1A;RYTUoi7!FYpjh^jFyOv-4vgVPKwX|{YiY%b_sd6&g^e*>E)TD;P+~K3(f3k zZ$?Jo*@-3f^^leOTz4As8v>yzbMfe1bN9?x*WM@%X`YMTl?^@bF)aal+^8 zipoB(zir*JyxZ!t!C#4O7mr}yY~(igN6^s{u{@C8vEZkF1-xLh^DQhQY%Za z`I(K3!ZGovJ3hM%8C(47JiGAcvlD-C52%5I52g|O_+UQGw!6u%FEb<8q$ijD<*T#H znvr4CSRn})WSlr~MCEVa`NO{$0Wo+&PB&Jh2=tjvJQI=vTb&U&@RjB2r5Mab_zu1R zA7MR=0P0Z=0>;aKXJelwf78Bbjr+PTFYg^MSFz6~(-@2LL-q9>O(cz5oy?&_1S^!w zl)ZnJ$>e9`Am5f$SdiiHdr4pVQ|}J1Y5G!cpJ-M2Rc*e{rG|dDyP?0%Z5HahM7cSk ziK$Lx3+!jmBh4&o?0hNmGM_EHY&Dh<%T(cuTrTpmmMH#F4tpw}C6Qgsiq$VgjKsKL zt84jfT*Sy-1ji?e4qi7abeVYcwYXhq?53WD(dYw-2sF*L)l(kbJr?yLDirG-i~eoo zM%c=TN5p#EJ!uhnG`f3~18?I`nc?r54(sAVFJu0}C;ISit$8g@+;+xh9I-fgCN}A~1++9AJ;b>JhA`_n#++Nz#C%JnQZ8Lih zpJhx-M1y~aM^Z@dN{WH5FOy;>mx=5yG2F`%I;kp)j5hB|0PGG}%i1xQ3ZnSa3L@Zmo zaIe)@FTL)%;_ypS9W

|4XnOt-iXvREO#KtAVz_>YVyIYgwh&d>Le%yUt7dEQ#0q z_=T6KisFa9of$9izYcAyXgbdHzzR^iXGoSrjzd{|w(v*bKPcx5??Unt_cJa?tqL!^ zg6!eMnUY7|jgXZ2{V7~ZKcl-4HqGOYK_*qCqu9eM%l$};@ z?%5G+&kN+-BRaQ_u7VU=hb>{Y6cM-&zIjQ~jc=UIpQ5p7>m?~v<>BUOu zKOQMt9FkL^5pi9Wq8@KJK@Z8FA!Ych5&dDX3ST0ZlNITSnpBAuTKryrGkg=dQi@1x z7!Wz}pv>W?T3D-VC=7dXKkbLWl4K=hfOf4A>8RkY5`DYOUx~gqyJ{7}P6{%TN6ZmX z3+2S-25g*|+4b&ONQ{c*35Y^x$$|x4sbWc2HTpqxx&#^2VpLv%ix5Og?%j^KNvep* z3CC8t-Na1cq56MgCo--qWfCjtJpZ0@W|%F925*BaySjXUfoJ3|YO$D*7O)X6*$k$d zIcI&9Qv@sgq!Wb|U8mKBUR>L8?ZVaZVL7Z*n@zk5^#5wbSaizha+P0PSAOpB%5vq< zjtclogI_^DG~w(Ty=cxXz1#g3cnS&f(5T)?byVbW3iJJy(^&h$V1x2Ql6*J4@C9TU za6?RllTzI~gB&3I-z6>oRRXM<>H17Bd@e|&55fPL@!lrx<2t$5VYlVcY)TFC2$3B+ zz;!fMC^%IyL1^jF3GA!1>{`S^3-L@8LFJ!kuAuw=DOk3mpMgE0!TW5rP+)e_r$y>D zVk)xpXb$X<+$^zcTV1+C?@8gCiKSV35ApG4F?@4lg~r2N&50ThyV{*tId*<(Bh|Sb zRYdO!aQj}&2(|#${u_0UknV;^JiQ|>vG=akWBUhE;GrW#^bJLC`>N%BPZmJseKDZ0- z)~9Lkjv#jxy{!%7jg*#3Yc(X_6k?3zSl+chls2ZZ!NNiFcjGt9x>@>&PH$Iq`qS#k z7xfXnK1b1~<%Ru1Y9BM}G1W*WM2snevYAGAu_81>ueLmT_)o6i59qijgSi5+9*hvq zhdj(lWz))15F7fqTo=B!>`H;mb1Ifii^^^hQjoc2lX8(Mh}`A5{|PbIeGO>Vq#590 zV}X~oY5x;m+(qH$Lzqv4F-QW=05DZY>^8;3y+hBb)wKnjt`i#e=#Bk4Lux3+N?HM% zp$h8&A4A)&0fXVk!0QRkr;r2p9L34Jl&8>26(&s^3b?%Iws`}&?0`XcF0d@`P+)c6 ze?#jH^aKiFj~s|BPiqU6$JxO-sKqQoR>1f; zDUtZqpURZ7w7cmFasvjI(o2SF%->P*;divhTz~XSM2izqQxc>xAia<=NbboGG8QYm zyZeUEU0{bNxebn)!fZivvbZGRBFNW2cf7IN;J>mYD*v$Lf=t_W_{mJl^=@A`1F<$l z1Jq*Z!;VMWbh@KV!t&IsSM-~;_MldnBYiDvabl11E>2*}T5%=-PoU+P%po5ty@@Fy zg+pOeZes|OGD{ta zK0SIKYivim(dfNztDVh=Wwf}`1oI)M^e7?9H6vO<^8c>MYetSjOi*W##;*1z=Gy06 zniEtiY>v^$UP|Bppd=psc?|KHMcpp>@EzhSjW~CauoFh2KZIV(3lF26?vRLB)K3sk zM9#ExEPBU*#+h%Bdg<6L#bu`Jh%!GmIbuq?7^ZLH(Yn~b5o1wnX|91!n1Y-?XjRI- zp-q_41!S*Z*L#yddGP*VN<_yzqq4;xnOa;eg5hMPz|4pl3`QNzp+e8Sf)=gNL8QV-@zJU##2 z(6@8Q$z71ANvsVlm*o7tvW2nK~(&A!z4%O*9d|qV@*- zCPQSdMp)F_-1H`TpMQePo7X!Ubpyv~y}O%g`(^!~@ZN|_4}FBeZ2D26K`zN?v?758 zoCc5-QytDV)Tw5oQ*?}0(P`NMCY=muP4JK-j!0`4k7e~2@TI|PgfkQdzE4&0H{S5_mU9qp4$PPc+axY{K2h-Z$wM zz{0*o(wA`Wz2%xLM8hW7sMKHW!n{YL=SL-s!l?hoF8&qtxrh7<*XH}zNJjsz3Lg3! zV8oeCvI)`X#S)XnJt;UB@$`fAR)8l zO6at$i`TC6pOd&J@+6O6qNiSfAzF7HsGY(|ZL@dd>jZvJuE2f#lFKfx6*C1*M6bCR zCIw$7@NriDSO-pVlwJD-bmMe*9}J9%?GshIgV?_fjp6+E*Rb5T#J>W}8a|P!#h;Oj zvBxI}k90uiAGQcM2@2oR9#Flp_Y_Y4A$xrXY1OnL_X)Jao}i^yBZjU+#Nu+zG#>4Z zf3KNN+&86DGp@7Zd}bnwJ`#QSvM4%@IGCJNi%n!GP4j`@O&6+qkwL561e#*!PC5l2 z(`)hQEf|;YW!iQ~_AcbB@juy1Y>UOhz9qm$S={6YUim?poqJT(Z=Z3>WFCt;;u@iJ zuOU)^a}A@>CvdKTo^u(C>f(L!ahyBc-LN!I8Vg->G`qs)8apoK0>HJGf1IXGRMTYUF(ddbo9k!$f z)JNmmqtX4KwG`~U(db&_SiKm$Q))%cR@D3eltm-xyzn7H5ej&g zcSyvaU!3$KnmW@whz&}6afXHzrJTxrh(77aNsO{Wx~&Tq-vVk0X7=SFxiIq#qn_`v=nvl_!5rka zPK0-OKaCiS$3>B4f|dLz$oc4rIW7`MboBio=cPF>9|rYn627g9q@_svr5Pxv#`lgq ze0c^6)e+KaW=NDbEsWDVCz{*)lXwB%oN3`LGz*nYWSu=4XDrASgies6a(IIb)x~Gv z?Wg_IHKq17ARNy&7>yQ=eG}k?UH;7v89j97@u)?m-(;XXc>(s&C#q#5rOies_1}(0 zOWvWSiQK4eiWk;%$!E&$r#@4v2T)JaM8VQUzg3{tjzy(+GP=g1`myXjHj+s_oT)3y z$+?4G&Z_eU2&8qw2>SEy`0KVV2XfINT8 zAX&0HmpJ@*#`(!v3splSap1|C;?qHc%`974-lJ^x?#44IS`j+nVvdt}w}f}Pyh@Ar zx!g=4e3t3yfp$SN(Akhr`m3rZJ6$w-cEj-$Ut8c%t_R-36tB&z_nlV1?s38^C3+92 ztl25B{YH2aUx)TE7JXopkMODUh2_*6#g0V(F=Y0UIj)dH_>ph|d5o}>j5mqt{u8R+ zyj6TIP?Y^d;02e}JJVBmd}CfP@XE3mv#mI*SM7ZpeP=qSyZ5MU<5;wMbfZk>T|fBC zH;Ci3TZ${6mPEef^ zVr%dLd5}AjB4vzwpR&baoN*Y5K08EcIr(|lyVYK;apa-Id09#F{W4emfSYTq zNZui(|5uIg%Pg0bU20d?RSo!(P*Iyc3Dw=-Lxo(M%b}s3Q2p~X_WWysz&FtB-Rhbm zR2&ZsZ9ebuAB>n8%@8+chOg%Z=aT-36Q6a~_D`vNXILGXKJ-XTKb-%$aoC_(j7#v9 zmF=#S;|H>hk@$SClD%oW3um`B?TN6)tIINS1H-DKABOHTY>2!ZDC=j-UUV6bUz0`ZeXRx^%~XnFA;mu!mlCk#lFgPYQE#QBRpTY(hPv((yHA zyUKOr**$S*j7H#ST$b%P({0#ho+PA?c@&pqcP!}^gT_atL^ zKU2P^oFC!_4S*MT0M>rv-Ba#_WzLpfTlTvFqXtk%CJv{sVutmxrvl~u#`4zy^)GW6 z%oV|+HG-#IelO;{^yAiXl#c3VVjnwpW#u-Dp!P@@(8}<#4#ikE!0}MH3 z<{{mA!?1qnG3Qjb!|3kk%U&vHhnRC@h&gXKoNqB*GTIL?-?DRcH4oV$kEM`@dy@;?hpg`C5aLqGEG9hk_j z8PM?jkS=P)NYmYar7MeYFvaS8=($FDn=tUDNr->xF8}h-{sDI4TFjp*?UV6!5jkDh zCT|kDWWBHfSCveu>e{kQnbJ#vOyv~kW5LOu2&B4OU8(fk_jfX>Es*18#&acM<@%so zpytZ~e7AvXcQqh8F;TzSYuN-&&-i)+j|Nhltd~kF6Li3m&Iz8CTiXIVTon{LeC^s>!obu3!t%=xl)wagusT+Ept2m+g6~lg2AR}h$iTP{XsaC@%m2oy_ z32Z*L3VMKz%3C!dN0i#Q`I!zzxo(JB2rpD34@+egSYy`bYMx(uGkj^hB?A#pd^>4m zkBb#9grBKt4xHIcY^>4R%(ed3L;cJwBB4)Jeu|!1MOL-u)+$bU9OwVs7hfR5(d|Pu z=ib2mPXT(3;bB{-td2Xpy2%=(b%p)lt(ZNj%ZavO)E<{@Op-dn$|Ezs(k9CDpY!!vD9e|wG%NA2JB zVWWL8Od%Iul9)9&^pt1ex_=tN`j64) zBnJmp-djH(%$JUs0q&dT}ZvjCYOa(*QvU0b+?))lqV z^tn$4=L>(1T*p+oD}%cEADIe8lw6UHNQYMZy)1!d6W`JxjGoeQI0rc>cxQ&+Z8ldEm6Y2XGb%fIKjd-rXH5+Yi#=W3=hR1~SUOt={r}qpz<%+2x^HPhas7Yt$ z23#4_L8I3XJFtr!jf}E?v;&%q9w$U{t5<`!8WMQdGf9jE2mkfQ+qY)C`VO)r+3ovO zoQ_a_tWIj9KH)zE-V971Y8fsP7&ENjy{T0t0`;6C4-B-nZFG~6^7uPnk|5oScEESdG%k!L`m+Tn3td_RjDSi-HCi3FVSw!ZRt;m506 zDTIUG4Xxg<Zx*pUc0;n}$z#6q6QKoaI=)79i`{f=y0_8C%=ZSI@N+bJ*^&Wy zftpEn;fn+o+?kRNc^5J|^S#;Lew3sWeOI=Z?YqU!9h>H5=CdX5p!~w|e6K2hk{x$6 z)^51L7koDo*S`d5L(k#94Db1Zw5wFMHWyDD5lQLx9*8hFA^yIXos$~k=J4T|@6mvz zpXW!s%%X1s`bfO=Gx;rFo;G^qZJd0aJcpe7qxbYz8pUW`aCPOLwR`sb&yV)}d{5(^ zEjxBRihm?a;qYx7#zMxq8Lwt345tfcVI}#nsH+L`Hh6Zp67S#S4L%+*P!2fFcW>~m z(7J*fe4Jv&ua^V&dEb#Ez6Fmy3duviw$wNFro8XMhZ~Xejqj#?cu!7YX)wpqff`Q) zyn+A7*Z65^qU^q$*(fXM@I`!9(95^-eVgyyiuJF00{y%{@&x9yQuCW5?u$a^v#yq~ z1M=YX$RqOm=ecwqUl?SSJ4d{7`MK2kXI)o@-}2c8z4du~p7Aa3{o`+E<85MX>k;b^ z7H(mc2Zw+1e*=L<_+13&xgeKJT{G25&L7Cb<5WBBt(D1~je|?y_`*%)2ahk}4Z%-a zmdKn6fB7@)AIc{v-HzaH9H-v~?4w=3Vu&t5$JCQI38zfhA_qjdHzW1_pQbKa zd8PelA?>jR_Ip6z8$wi5t?s+aJ`}#nBlhuTqP#-6`Gy^?{GjXHp8DnP)9Ro%KiG3V zt@u?$aWts$^mvWwLFdIU+{@j`vWesa_%QXh%)Zm=t6nFhDYXl>j?g}TIrOSZ5^bCC z#3pK*5i6bQnbtVfGriF!z2NFPM9dC}8>rwMqDA^B&mz)YbXr}to%S`UaxA)Lgv!W| zVNVd{!!h_C_4_0Gv_h3ly%5IOyN=36j{`i{=o!Y9DdyNdl~Zw_V*5x=@kDUZ?}$>I zJ&3Cb*W0)r0^ah0!>xFxe1PJY;*{dIw6pr$Br+8J%b0Dct)`&5bnkA+tAZo-zT-N} z(M&1DVL86rhX_nVy>DhH6Y+`ib2rj+BKPQnIYLeimE<-lXURwI75O;nz*xnh=%Zsc zDa`?ifceuLs7#!cW=c{Vnc{K!-KW*|sql3VAC?hAz&PdSesEJJqDR?5&hig@v+eaI zhcO2V8->+}yND~*^NcTj(0dOTrW7+2{oy-pzD&i8R>Y$5@WF(vW^x)Ku^F6eNVMOE zcKAvVe3d$nu9|8vx`YNp^%-Kr*@=(ge!_o91JN`}_svUII;mjZWr^f0s+i>)s@cpD#<>Jk7 zbRcHKcQ>49%i;@eS!Kk@<2r)Ak)iE8hWlfd%^XHQ~I@h{^9oIq5SuBK94}`K+dbN=CV!Vdu}d!9#9q`q8uuGLizz0^CbAX#EDfSQAg|wwEZf^*c_tkTt28F`Ax>ZBM+X=la5Qrr1OWpl%Nqk?tY1$ zG0Uq-G1G6EF=)pqh>1ukX8J7``l}kh82r*Fe!1~0PsbjmT+!5Rlh&YwPn2AtnkAFM zlSo+aF;pWfC30-p3K6t9NKlS*ed2O)hxi5Xpf6yYMqIsb-bH5PPQO${Y?O~>)_kOr zV#Fgo8P(bNLNSFQ6EF;^RQEwvd~usD6o&MECGq(Ye!GNe=#-D_}m`TTj0`#OBsk@cuq~`+S{GHO?Ix{6nz);0KQYRq@y)`1 zzsXVx{&-M*PQ3=F-LDQUu-5x19&wu1L<&noR4c6amiSicm?KtCuJ?N{B!m2w)9RBw zCt+Q53~+kL5)KxIA-~!K%fbb3o_uJ2-fjhAg>tA7`w0rV=XS}J?kbP{^wI(y!b#06NyybalBZ6A* zqxq}#-nW3eEY7JEZF)?dU7TU#Thn%P$Yhwyv8@w#Gp()Fsk>V%DF!D*=5Q2;EY7oe zh3vi0sdLQrK2k)K$Gw!kTdLEZF-hs-CYLstoE60=omaj0IdyLFbFsPRH4fde5{%4q zRNpD_ZUk(%`2)`0zU7^$Gj&k{$Ddar-voko#Od<3a1rIBTiG z-H%=v3(XFx$Bb$!ZQikHYdk%f9bmf_>&s((*UPWLHd&MU9B}O^pLBd;+hgjyj!e}+ zGHgui^&aEvH1}d2GhsLAEM|x>24dF-%N0fg-ZL-5{|>+J?6XC%h2OU#U}@(<)I6XTv%pWRN!e#z@VsTYFZAPj*2>p7Mfkh z)WotP$x=zPteZ;~pq6MlX5Cw6-3D9&m!x%a=+=Pfynry@|I9$y{l4yZ=l45vmiL_V zp7%NXbDrmabVcT&HZpvI?u0G{?YRli{XqnC_m?+xlcx zcjR2FYrMr~Qhv@1yO7(S=Z%%|PN4oW%F66sr>{#H@dBvd-W!Jbb`2yFYgz@8XR-Gb zdU^Vz?V=KWz1R6=FG^iNU7z)C%5FdpISfw48=6Nio~oE5di3(Ciru2Qm)Gmp=WuOu zCLi)v&uW0c?cLcxqE1yjk&D$?naGOXg0*_MrKsZL+iLEyDJdp*NSUGEDC z!K)!nH#2+6f5c3|yz7!`>vv-0r>?O2U0CT-t-+!SeI7wRvAJGfU0-Rnx)SFhGUz<{{a_8h-&n9pUB^5yqxsbD_m2;=)T6^S_XdTW# z!kE#JtKcOG&IVP*UP!XU>Y}rg^@uSk7&;Kool;daiGRAB0Mt+#7LiRu*;6Q2qM{xv zV^Py(5~Z3FmIs}=3gUQyXGSB}G)cm6{C6PFt775h!AKqIPWfY(3VfS0mnD${vM=C_ z;E;71umcGAXiS7CYYV=%*Lkx?kzI|p*uU@Dh53rMNy`6lz@}? zqC~*YI;cCOI{+Q+9%luAmDG+lo zf*18lvKrO4?2D}&*A0U@QVuqss0N0UFoh%8)Mlo;* z0-Izx4CIE0T)VccHe4lG>!F>tHXroULSm!;d-`)gTShr3?YyFQTUdPxFL!?}!qH|K z)kZZ@igK#!lF=VSAgjeBN~3x3uv|EO_r!7Q&D?j&O79Bb1~WJIYanX}Ibo5*OCMSh zX(w!`IfV~Y%C#yU2z5%&ih|-8dA@rZ!;)%q7cq$$kjLPna|`bD>A8E*Y3REty*z!z z<+Nc}HLoF2AFWH_gA6XG3KIAfn+5o#emOMnEgo(1JV&@h(k~cQa z?a_~OD$d7eGr*SAgNJB=TqS zi!0TT>;*^rWp#?Sy3V`s2--mZSU~q*6f^3znt{+yD2?O}^nfcs5&|vIJ)=7oi71}5 z9|xCJ;1CE527%yFvSAnvpM?=5P)c3cJqo)UE;3keCfJLcBym=(eS132;Ct@8Y0&4#&zs)aTh@xLtltt-E_Wq9qOjb6Qg+D z>RKkAwKBWeSg$4y$S#8qaTzS|fxiLoUdzvpm$fl6-!{2#5p5CVOpyma@1Fst-qdu7yO|h zTd0>B*^ZV%+}>ia+|GNU*CvC$uz++4N#s*CHFwso_i7@M#nA!ymqv%+Uvdguuu05z zruyieuI22teRtNH>^7#FNnxrwY&87SIOaxi>JNQkcimwMgh^AuWpu~$gke;)jz@xM~nWZH+rb4%gcVq4qd;h(BC=5kl?6KDxaNWCsu3 z4t9fXIP(;`k!mRII-OfiQ8_fsQGJNIGH~c*;E7ghWLe^7=rv^q-Z78KY$IYwt}P5T z(2xsmoS%Kc2!*0IF#j=MC^5duVR*=NeeKF^pPIZW82z91(Wkev!Z2f5?M2AH$lH=d zIQtgAhJDk^8fl|v|3n%CbprjHb>U`#KHR`V!qsUDMqa~UQjs?goWU?-TCMdKyAZi# zzK7I*hvc0%_;I)IQHgEvVJxpg0x*ugrSJLOMh0^nuQuqIoO{k6f!9Ryq!Ql)b%XC) ztsqyN%(7M~a%;JF3jhe@r zZ}M+`wBLx^u#{DrN38R*=VeKuot9^XWVMPjfd67(RI0KlbD3D(w%h!Wetbn(#mwx+ zP@>viM|W{l0%fCldN%loN+vlS|DZUK@rn18$u4K0D;{X|kfM%XW4(lL+y$ytYRWEB zl<<4bCHD}vb^juK-(m0C7NFo>!rA*&$V7bWj_s)-;l&L@a&7Bg=TN_8)jCu#pVg`Y$mG6995aZUOJ2a#bRKe7Onw4P<<~w|Kwkw z?Q`&zw$gB@ySy4bu#{cfY{dJWUm9plf?*8??}L0vKSmB#FRJ-FCjNPEF3%kr5{>X1pT`r@_=_#^>2*2pkPIn+dXWwEXL*?9!!_i*?UH zM*K8CbgD4U4{I*Y!AS$cR7o?V)sA1xj55(gcdRpUzX%JwRtEbeqUy3~qPsEknDjeM zCVi-hQ?=Qa>X+s;nH11hQJ4g(Teij7#vJc*Yw&i2T&rWoS7|;qd7Hjz5UQ@(iu47! zA?2HR%p6JQ>-L3*;Dlk9>x4$_IAXSyGb3kP*^$I?&`fo_4w(0?VQ^32ETDd!=>{fX zk1PSa2a7E78Jr$|zecjB0xka_dTyR$-5j=6!$R-!^*no_WKyP}jS~pl1VRqF#RR3_ zWh+|4jSXX>pyj)7jn*!ggGbRb4H5+}c4t$0pnHsCN)Nd+)r1(bmNij4E8D*&jO98^ zMZsDIm?kvt6YjXlh@09Mmz8~HqourlF9D@of>Ory1Sin)#p=Fa6K#R0CCca-5!TJ7 zWtHsllyqC=Ecwab%Xzr5XpOXulm5AcwfAV*)WGv#98TojbMLQ9SnZA*>yG;^;@bM+ zva$;{fpVQqs9bAfmE|^0sjz*9_I*wUen0H+o!J6%miS8hId3H5c z^i$PLnz`;S^pf1|CU5DKEj5Cw6zBoHsFS~Tn$OtBy(o?whPI=C96}tKLROG{0QNgZ z&XJzy8HBHygGfmgW*N2;Cq<l2wvB@a$8|QPqs^w{>ET+ehx>O(Syx%For_M%Q@eL z+9fB;7log%8>+8u)%b;#qweL>>m+Uma*WMl$6dBX{hpg3G8q!Y6;_I}?9;i)7NXyX zgP{Q^K}u~XFe5@Mlvx2%2DfPiBFwv1sM=){sa~=9AzlWdCvb7KavHCEAaeMH7pu0~ zBzTrdz%c;@egaybKc3v=zqNgidbYyw7+-0m;rAP$#|GYU^c=W zfN6y3g^AryBoFK7W(Sv7=%nQjPrk`l)U7oE>N5M%s;cu*3$G$QG z8GE*h!MR;REfbm7v2z9G0lw3V)50i;eh@e(C%eS%l>^YW;P-+K4)(gEsH_B)Cvo6C zO)xDm6zf16anCuvHwLoHRD+3NKS24CF5E2V88f!lR6fGUINx_Qu*5O;MiL;)$Q+_g#_Meh(J(=eS z@bZU*488MJu7j2wc;5=0?6uTQPi*q3-p`ZD)+aGrvA~K{`c?;<{9thBWCV$P&W2lb zIq*sdYxS)THMQA%cPmVOFu!7DyIV8yuHikg2DB~O|2Cn0(XoN{!9?`=kKqO@cOuqy+8s4it5$Lbq;RV1$6dYWIAh_NtJSS8Vm4+*NmtD#-EQI8(JwKs_Nf{pi=la{gO z&dY9jyO&ML(W#bXU?SlLS_ef+^5AdK{&M#A$0{JtKw?MUboRECc$*kU5=Jjb-$1%~ zcds0-)woaK30`Sdw8-MvI%xxmRkz<;dG>a?>K%(LMV`Xi&Ez|qUmVUyV!5j>74m?F z7e#(2mM13$O(bUvGANd?caAJeVUXpxjrl$sZYCu#P6;kMJ=y1hHBHyxCqQ2#%!e>% zVWz?q!z_TQgmKH1gUfJ)RMha!ecdE}Fh*ZGuI}&2>-aW_j=(|Cwj)F7D6Ddi!jQ0X z?CL>HW5i{6k$c2-IcuO}C#jM5A!ZnmcNPp$B_0n!Y7*szGWQuXY?GI}yud`x^xxpQ z8!{1lV_LokU{Yb!Fg)sj-nFSh{c%_6h+WXF#CtE|mOCobA*qKni~F73whGim>hVE( zAME5w+^B1U=w!FNASYFXj3883AXQDjly}CTqMQ}#8s6=ZznKPJ&@+U(dFRoSWavAZ zz^mmrZG5elAm%fO8PHAruk_NC)GzI3Mzz}L9n0U_Qcu%&Gpf%e40MDkvdPAI-nhG& zQPNtVywI&RI9X7g&JpQoOa7$4B@63wJUk3P-HBYY<9RdvPPL=LOz(qZq{s9(`Ie`` z%5U=I=yQB<;t@VXO>aIq!VgkIGI<|~+{v@@ojh0hoFp$s(8dU|?M%!Oet_~hK4>bp zBc|#6Z7%{Ox866<2G>B&KELO6xJIB|j&jB55R-@wxSVf55{#=R*gZXOPUC~X4T!_P zSqR;7mQhuygLp~2LMsH4dKPXA9l-ju1wmtaLvKs%9=ywy5NwUniILYj%%r8j z&92Bv=7SQcoJmlk$KjlC(tmkk$AJF2}b`EV+3f?Xwc#aaZY(#p^Y;z zqXOgG8>;%^>T~qJ$E9@o`Tr5uY*XhjQGvis$M~1@JICZ-rE3L9iG6}mS)F@bcls^vkRt*%GRnaz}E+>&{>3Gb89CxWyyJZUM*)L$p@ z*$sl2NzGIfFvIE{8LSU6OR@j&b@ucOaE}9tHc34+9Fui;#i%ch9ILMd7pJ)A`cLasw|_e8?g=H>Ipd7C z8+Rmk(>ePfv`gOWL9LTL`~bNtW}H=gfV@cWvnIQY&>79_asA{C8RnjMMTgMp(c&dQ zdHcDc<0mH4r%fr7wKmAYdBHE}_Z-{B-PYQDIYo>Nd-awkwtAQ5Mk5n5#LC7ft^W0_ zinb`cM;V~!T3H1o+ZLYYgO#BhJpEvON8P(`wRv-oXdX!ihg&(w;l%8~ar1Yg@3@|P*f8vgrDVew%f^FrbGc(oJ6k~84MX*XSq+yS$$GzNx ztQf0CJ8W{GOMAk{yXV(qeX?XrAWN3sUXkpPUb)qX`;W`hOeuyWa816mB^!63HROkn z$o7j%F)%#a($pLPZYQaV)z8s|RmgX{oKN@Ad`a|$hE&sen?KeAL-qdd^+3hZ2tA1! zTtPX!kORzqS0is`T7}_|Wm{(pV_#X)Did?BK-aNc3t6_4njsgN(ZASE^SOzBy948* zErF_|SR1G46lV01$yGR&9kF#pt?w@I@eE9|d^9wybzL_1oTL|e*0t_^37wDVd_vn2 zZEuu*w7pUKQNGgCHM?|Afv4mLN$*$g`9pU{rc>f}VJg3IisuFg-SFKVt)pwI2;Bg~ zX+8@YBBWfnUA|keU6g}W#P(#YA|7yw=sUMSW&`zfwf`MJW}p}X1C3-vx;15yw*IYl z?<7IYgP5Hdhirl}dL)^Po1t!7#{-*y-e&i!l|Rj5w==&s4X6tQ_jRZpYSs%Olp_uN zQ=kCIJCz8-SqVZRI)WGsD~b4bpP#`~hP`XMz14F=l*Bp?G7O&7RVOIM#Fsb`3MQZ1 z{)|#^@J}cOj~^Ew!L1WZuus_0?HmfE0nxQs;3YCUfphNGyyl&;|AAUyQd86d`7zG8 z$#_jHx}009T9gK)TWid>7*ladhT9Ucm9*jRifG{GyPUsZzPo+36MBXmX4Y#w zy?K(N^WrYswiA%Ej#n6=qygX%y@je%Ij=4Y;?2v+l>faX<7DcxQ7rXB5Oa z=-uz+4;(h!+nr>Z^ySMQoHmL{AwzDjbr%ed3&x#mxT`MIL=h|KJ#}|+e~}2hDK4EN zA>efK5D@SA{yU4dVeR+lUi9;Qw3cFr#rV6Nv(K17^#N#6Fh(ax{oz7@v$4 zH^mId>)5aYn6GEX9+&E#h}f zPG@qLvOe0VuH}FP&9y|k@tx)ZUvuXqH##}!=fUI{>Xr%eU`Cw1{b~OCv;lF9&KG=0 zRwuvaofVwUXoS|h4l@&y?w=6>xe-52vaC<}kcC44GV3u1$Gr%vFso7x5e0zGtU}z7KBCUO@Tx*}^zptA~k~tuA ze~0)zXvrq&_KPd#61ANng>CEEp4dT6N85l(+InuP#DYXlAMtZpi<*GP?Z=Gov{Eia6~Y;JcsB8;;c1;#%Kv%6 zChPlJ$g$virPf5m3brKSzo`LVjy(Z=J1zG>3;y#Yx)g;+L#{u(lbQkB~dw6*p2$kO$8Rq0|YH0}!XTK00b#?Y!JK+g43T&!s`uNPfZOY-bVxNV1Fdt;|H*8Zu!u;xdJ zvxΝDjmKLeu@b5x2(Odk5GHb*(bggUoTrLQuogHNn~sEmn1~)>8``P%4qdjIuJx zOxkf<9=?-)W3YvOWdvx)`3bDFz9gU-C~Rl^!Xd$EniSwzpC@QglW2?DP5Xd0vho27 zxkKqlze4*vRgque0Hj8aMT}0viYPTzG$(b38L??Q!pWKiRDv&m9 zv7HGCZ^20{OT%bfDdP6~L0QmCt)Una^U(uX%O;EvkQH&fua#K#w*k@n4&grR+SV=^ zzrXcdzWf@4Hd&NGTPAIxSo!BEfkU8eWl4YQXAw?g(dSd`xwJL+KXRF2`X!Wyk>v|Mf`m~M8H^kz zkWr5;E_rNZ(eh9xIjmY$+HHd_rJ%Mfwk-|2> z;|=?403qN`5_1$GKCtNve5s8L{iyvd-YbWF4!lBYZ{i3?ZDb^XP34e<)c?7J0O5=f zxi1mJru#Pu^}pm#ykHx?2R^~ET5A2qOqlqtU;x&Qz!TuCA zs2xTm%ZCujtw;~u>W31^mIxw=DjOM9MzV`bOO!JT%9bFJ=ST5(D2?cRKxxr$%i*Un z9_V|X(dS>ZY|$#RXyuBLF!NV0D=9aX6s;;LUR1UcgnwY!@?`}}OCBUMmzFFgu?tF< z7p#gU(aTnsmc}5j+9^ar4b8W{&z4S|Jt{kIys~Un!OB&OmMxT$$(fVKD;KORDN#nP zj#riztXx=9whC@3i7Jzl;_*?dm1PqW%cIJb1s-dG$67ieYBebmUduea_2&#~#| zm4;6~{`||zSN87O_Uu!e54`vH*N+`NdHU0{=l^x>`sGF!-*)%=AO3Cspr-!J;dkD8 zdCcRpWkBMvAz1$ z+V?FdjvU(mW@oR{@#A-`zkKx1uRgnR_2MNEz_5Dd6YHiuG=KKw9BoF(;DK@>>n)2I zHZpp`_>@sovelEO&zv{+u@&X(7cVU?dT?Cg*vP2(I1wZ93mp`wc=zDGx9g67c`8KxQL2FyQT&cmQO)!}khP1_L}vy6$ScK=V}c}Dvi zeFh%kA3uTT8SR_&S;8Mr+%6hU^Q3maq5YS-X@1nu=kB~`!?BMBuDr_*bCcZJDV55(QRR>Pf8r+pPjNx1tobuCb2BGr&X_*uzZMonnEU5U|62)C=hLj+ zgz76UVj~M>f-+A}$u?>ED&=DZrHhK)wWXX|P_(3E)qjR({SiKWwukV=$WCi4SXPF- ziyu)+rKHG639WR$3w1k}Rxo~1#Y##e&pQ_sEGorYAuE73Eq0HQ*rlRXO{BvzVMUlj zh>H~vMk-*|qpkVTsfq{%ewe$~ySso$jFiO1NC@X8VJBkl8bYTv;w2OlDRI%RgZaya zxyzHk4Eg)?&|5u)r|?(MRUZg~a%*hi1;mpFS;b%4B^`_9R_~CVk?Bv~gocC67#q9j;P_2P=Hs zpG-gFzy3z{J$*S*{CIqU@2@APdF=}MWU2Utj>V?YZx!9zzoU3>a>X^@H&0w&Gx*l! zmWt-aSK@Nt_d30<_HW{Z6SfxzSt^U=9}H?&)-29iQGffJ^fQ~DymU3R^@kfvryal4 z@#*G^8z0(PsyKUKN%7jw!k%BwmpqdCNR}4A+zUZwVEU%?p zI`Q)x=f<I*H%&2fSVm-s$`8DWApb6DBN`yi!{HA~Ub(r;ce$mJ}A0hBqaaY@R|2 z+yA{oRQkkQOxQ;qlBZ^U;&DZ&y5FG2&W!OXNSw>-e;ax%Fag}H_ke`dAZW-(t`Teekk~t zZ|66U?mXWd6S>n`bL_y^pAMXGbj}8!VB+OojVJ#7{!z~@AyBlj) zjhl4Y{@&w_dxC~t6KouCy)3}H==)7+#Vt}W(;M`jf|FDxuEuNYGrViPS{_E^}Z-j=wFTOVF~RsKcJjfKl^ z)^~RPcIJ8QnGXhDe!j-=^ZqMW{#MoS`X}d_Qm41y%xhbCs$t=*5C48cbbO+IOkLL1 zIG?86FzI`DbGR{vwSx4Ie>2>id2```-=1HVwC2nr-L|6z7eY5K_;6q2@~AQ28K>`f zT=oSw$@^6O05)>uFyYKIX(#^??R~m#`@_fL1dET(d)xK(xumbG$DiHX96#vYZ|2sV zE3O{aUi8bW`xmd4RxM=@io9N(IL5bi^Fr}T#VjIxD#x-TaP5ij-i@n$A~o!NS@rXc z+kMVl{_%s~uCI%@dCmJ$aj z?DgkmABWu(KK$HoY{C~cuJ!Kq2&VYI9xRl&c8@4M&(#o4=y(4)#n3(OHBMi=KR?5w z-o4HrO@pz9A*qbo3u^=EzP@$IebKFdk^di2)MP5xUj}T$es}*7gSvi!9)2b1kN4+i z{pA@$gK2p(z%xL3xPAW_?|<>DiR1S&fIh#w|D2Z6M~VI4pF{h79{P->URs_kq7FrQ z!uDZK>yOfBTWS7b)WfRr=l(I_1oI55c6;#04k8dNW7TlFf81c~Q3$Jcd+;Y1LdaCY zs^N71gi1_EgjJKipD2Qma>ALBL}$?uis@xX*}ucz>Mx?JVMQ-S2n( V{<}Za-k1`P32GH^~KwtY28Um!5;4J#jdA=^= ze^Nco`2T)Ar~({9%4=_94S(ynubk~g%9ZKwPNn~wW>Q>*oo(7af(D6^?-=!8Lk z1}XX(lur#)LW9rO?`Xyj>RgQycdFqx3^C|k3%yr{v2efd58-Nrc&=Ap?e!vM`%FCg zNgO!OH^|6wCB*fkzy$;1+1_~ctN5V^PuGj}rEI^i*I2ESQY3pbwTx(YZd!mbbfM)^ zzSMuw2YT6$`+%3o)_FF{RXJSmV9$&4^Wvhwsmx7Yb_dr_`t((Um#}4zm>URX;^N^R z_EB?y=-J`*m6QIG-t=lg#>Kh8v~_8oWpbxzJ;!;vWIBQx=t<=66w?Qh^5hIsz6+Y~ zh{Jk7Ic0{Ikn;G9ATN{K#@TkR{A#$QANdi>0K}g_tQlk{S0RDx&5$;z0%z+cPkgIL zp2dt~B4qG%sOIIxeMe-WkK&P1FJf$N4k5u#KQ!49)S>A#{Zptj_V}j>YT)ZXraHEc)J#0$i$|kZk42Da;Ig5W zP$7*9x0)hxCzFpZ&$RsdB2s8mN?HbDY`ZE5J&{1spN1J*YsD3KwpEO4WhGprp(d zze4Qn!V<)CfHMH@!T=PsfxVF3O^)OxZH3hf%%c2(%R#?MO+sY;Z$}t78x;Skns+E3 z9e`e>yz8$8jo9gwS2s#-H7_|+ibvm`HNpA%qns{H&TD@~&WoCypZH-%Q(ekI|636@ z65kY^Pv=@!XsPFbcw1+rAK^jFSgxSffUEA-1@r!KpnDEHY?Qrbp~o1l596X z`S&vmtNp^lsv9b(4&g>Bl8kW&EufAJ58OLfEtR|%D_^MTo^1JzNpw$AD6PsOyC)cn z#XG3}Vx<87@dRKu&w%!v3)Z&ZSwgv10Dx95qDvUo#FwwdU;IyCPHPaVEdk(q&DCz$ zhfA}(%y*M@`u0^M2wr42R1j^`V8&Z!{5GZ{A^FsC6d>}5Tq2(aolM>FX!&t+yC&xC z>ou*@OJ-@A+|=jmcNGd!kyN9!;{1S1$d|i%kmA0YXVsUXLM8P3a6%pju|_J)6DjY^ z@G=W}{1Pw%JOtPbczCWJn#1P+Cv-XwI{gmp-uwANgkcYm@~h*d&i3k{cCxWcPeEid zGQ;*09jC*j&j+VtZKm$quZbw+>(5YewiEaQGgm+#jn`wWw94Xy|6!{)2{00qyt*pR zYnAO<8#!mlhg?2bgW7!LGLVyJubDtQxQaB1gE;ELX=G2SW`r~;8FqMJx@N+kMm%o* z46-`~BTylwce+OLuP3cH&gjAV{OMK_2{4q)MfT1Nz)>!;muxQsyL3ULdc-#@*SnGO z?{IVddL|LAjlmiapGYFOPv_b$9Y=`krFfKwlow)vm4{+R59V`VmH#D1Mtv=YlwZVj z9(@(&t$pCOplxHToC|CNB@>w6Oub0f7{R)j3JlXBwo41<-2Ein> ziERPKLyrw0mrQIE1;hy@_oJn7?qF|8Ob7Z;39>GNyuyTQ2bx4K!7IQyMmsbNaf0C0 zdjsP&dtvo}QqWp_{oESL)n=dr2sjBBO2|hgy$d{8`coZ}&LMk-v|HpPeJCD%J&tTT z=@n5oR0229KgF3cT%?4(nIsm)P8?#ED`B07vRTw3)PJ!AX8BUzANA%SVqinZV1~N0 zFm~;s$?x+>hMB?a$T=f(L_9N+>#@qY9;NrhxQWT#oo@bK<8krE|FtCe(>=$<#lh@n zUKI5qN-!_Jp;|XhyT2#j_(;#B{~l|w^fIP9MK-W$aoHmLEt6y}J0dO^T&UvIO*wL3 zA%9rR^x?tIoV$IsR;3>apN6q894=iP4pS;NTcmKZy!z(MfQDW_-opV{tB zRcZ3P?K(UM#g!qj3b>t2R~Jk9RRx|jxu7ar-Y=$v1SO7_R_zy!q2ZoI4*glU;T}ed z>)bDjC4n5cH_`Wb808mJddb;$Q}+sp70ylF0FmmKv)Gmm_>L*cMkLoxfraJ8qkJqL z{b)*s8?Jo?Ui=ZPe>>O?v1wu-WZ#Ir6I<789`=SOe)@Xfa?Eh-XbWNw0nFcp#Q&mN zx4bwBH$@ww^okj!uYXM#&H&ORrt8?IEE_6aYjf7xCcJL9G{bJAO&4-)g(f8tZe(oIUY)G&OE-G$Q^Y^MyM0-$9x>@!22 zsF8K~%H5546kg3nX^kb35CQA*4(gJTAjiW#EY zN6lvQs7_}dWta-UYuxx2?i&|FI`4a4h+$iBL8)vGWVsKzmEKY>%4?D7CGHqA`IW(N zW*gGSbWtj%o3xD@aDf}I;2^$f@hbgFFA@w*HA<>kY7%4g#BYK6C&(PrO<g(bcT-j%h)wXfsUEPF=k@Ps7}8G=s3q$A;T7Fi_%ZaS#At_PRqh5 z#-!vnA|;o?Jn*{rx#-E1;w+hU6Q4l*J)N(IyMUa0IDguyN}MQ$R>SjWS6^lD>=UzP zCZLDN4v)F%O7zBbWc(z^Kpb|>uQx5T1?B+Ase|)VN0YHZs;e%`T?%E;Xkwt@ns$nr zPL$gS&5kU0i$+5-1B4T(=St+nB}1H$q83OzP1LNQr%TG3D z>xt!F4TDa0Yqhm9yP__$O|%YKtB|b&a8^}TwMEWaM`8<$w{APRt?KT3P2`3aR4-hY z!13t8nFUZz8M17wt7VEl4QF|o;$MgFP?^;S$}fHmkAi(4or|BV;k+pjLuP;wmN*VoBv&DTYv4&D)R z5k1yQ!`%w;Tp~V0zd<8^tzbC%uL)dULhhw4#{U8oYnqh}eyb5IYPIR4+L1Y|1Pr zxT}fo&Mb%Z`We(*N9Ci^-74epmapukWwe-)-ftb=iC$PH6@cgZDt;O`3Zy$_9<=zp zF}pkQhL>4R!~0u8!WWJ65)$>irujM9HY`1ub#eMA#p8kP@~pH@F|zS@WRFT=_9?TQ(v zPt)lQvZV~!IVo%Be(}<|A=St&#NV&S-K-B6O@xtfWUH|4$Ts0#Ci0PtDra=#y|(d%BDZo(y1HmjC4Aj_y)9nMc#K#iFunEI!Qp%6+{bJnoWVL|t-T z#xF92EW&rbM05><}~0omP#`>h^T}zcX*y`Hv!ZuCsnacZM&ho^@KftJbmw^$&o}ko<6ovN(<7EEe-oIkxUW&9SeZtN-jn)XapUyD0l64^05ogY{%Et4RRa)5$NN^ll;L9cgf zwxjH553)1QQJrZ!`&EwLFVbgm*Z2Il`9oo*GaVbC$8c~^HS$SigDShP4{~D}!Gn`<*}^h6$o)S(Z-Q*ybrSm34368`E>dTiPF!>{ ztOLpBLkr+k;HjiBqsgiougTpAl9BT0EVS{%YBKldvR~;QR?~p~WzZux);?9Gacr4| zR!tKlvko-z%xMDIGh-Lz8gpY$U)~QI=s<&G;bD-jf9}+n(Ym3Geoo&>A52%1uIWHD zST(Efgf@O*8QnRk8m{RvKf~_sLDlp}En*uqEplfGwMo+>iTMubQ8%ZDF@lY6g%>Ds z9n+W`G73k0jPSWn@U3oV9Qgr8Sna2U2Hy&ATDVQle&d9UZ~JF4_tU4_U6+mGe$g7L zQy16fgI?{kkjF&>Jv?w8fYXpEmG}#!)$Mn(RoQrThdBHxGbU1LDqdaZABU4Q`sH7@ z8YG~|M-1FFj%D5CtH2c8{BbAOUsMbkPmYtO!rafQn~jAQh(j4AB^`d8IXy|oR?mAT zef3mWUmXRQ1R&!PALuKeUWnNJHz4-IOvH`>UI&=SN-8u4O@&mjtWRH!M)cR@Fd%21 z*Orag9|HXwz(;s+p+1;CL>IDrfA@BjLUO z+|IVW2Sr9o9W-gO=~+sXEy#zV@5tVyvOBGZ8;?zcNHC)Z~X}F-qEvK-`Ql3-b+CJBPmhAF0*ckJNSit6O;~8V0JxDB{#J zl5Q)ulUw!C8CEEQ`<2MuHp4=WfynehY@QqV{8>jInP;MYF!218lSj)YhY#=W6vu|_ zjfWfT@=Lo0cXo;^0y;qtZ}()Ec`0p-wHompgS1eQ5KuOUC zco%r!R`xE?WYf@Z@j$ffwN#PV|ByQ3+@R*HA+e)} z36wXWUUUJCXO6}(N8>oi9#@N;gc8PccWgNZ^U5lFx(DXR9a2Bzz}9xTGE3P>PKF*==>#gRSD9LP-x+;seSy0IZaQ@Hhe5MIPwUaHdryS*kyThXxqKVZ z-lf`HL;^eM+)TJdB|}W!NaAd(dzm|FJ-Ydy=QuyS_oeVL^)n}|8GJh@yHqn#)DUW_ zuSfas1nTQuir-aVdt?&%LQQ4$sPN~3vU(c6o*xgCDgLsu+BYUkwueJQO*IowZLw~K z+(|D;LbvvvY#LHgKUa$A4jbZ8@9?ot@nq4h@k zbmk!|%EuQnC13x=rVT1{e@g8n#KTv@D|@lTN!_aIdJ*p99BDz8MH;oz%W^IpVYe$Z zMNQKp8f!zlyF;MQa1%Z0uY-5m4&VUmhVMoKv-%&Pj9)=YTqT~_*$>J{dLxQg-}Ifv1rzAIjARVn`7C4v*RS79cB=oP>W2IXe5WmP3VTTEYJEyEkn8oFg>}v;SPvPeo|{Iqb8jV`_(VFfhJU7ttbC-U`lHg zwlv9Ytp$zR-kkK`yaTvhH%CL?2F|qm0vm6qU8gA?kCoDNnYH-DcvAWus^B~dvov)R z&3>k;91;$S8!sRMTAj;u>=^;xy5@C;Id9pt8QsL5Z@9iyLE@&(4#;jCxvrJ9Z`w>| zdbnx02`wuLb~b|TQk|QRh4qu%19hs|SFWJ@+<-r9GQe6Cm%&LLS){m9W5K&rgR?97 z6O|iz2jbw^`7TUP_;$Dzo?gBAB<}81o%r7;SD3nc{T0 zE8N*=hY{Zolf4@TJ7Dr{-J(KK#Mk-C?NFKuKPi=tBH9AkwFg74Ri#7g;qA%=@c#?D zR`m}$i_-pEJ-Ah04VsH|*XWp4Q-e$q8yqy`1V}830Pv8ho%VYrl5=2}S%&r)o(Xa= z)7`<75r!VL4qr#>A6l+bt9gJ&!_2C4LwMD^l&L{eGwt&!rBqp=@fZi`iqACCQa-1Bzm z5+#sU(tCZ+=Y63|%wOzz6ngXmj_~*|@gc_tL9~nsFixwK{#H+{_44dRYAqTYM80yO z38T=u_aX?@jJ~hSP?%Jr8RX$6w~XqjoIt~gtfQjl!N$RA^u zA~qc(3hJ&lW+j508$}Zm_{|}78_--|&xg8^0j4Bq-8R=r2#gFcQ6RSs8aDt~pi!3x zIW}D$MwrQ?pr%LIpu?2wns{W;wf{X1_edwBap+jj7GY-^Ao+Wx@y z`x>EA{e!KjwtfXKR`YcaZhrU&rL}x%<%a6Uhwg{}1|@|1VUk1!V0sRNhVTPDG|V9V z95&2hZK8-l#<@C~B7(YU4j;pmQKQwtS8}Zl#80iH(fD>f;z|+bHleyZ))f~?w`;$- z%E~)eJoe4Io3GVwd2A)r;8&W9*fbuo1ppguh + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_SMARTAP_AIRLINK_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_SMARTAP_AIRLINK_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The board provides the following clock sources: + * + * X301: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 0 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 2 <= PLLM <= 63 + * 192 <= PLLN <= 432 + * 192 MHz <= PLL_VCO <= 432MHz + * + * SYSCLK = PLL_VCO / PLLP + * Subject to + * + * PLLP = {2, 4, 6, 8} + * SYSCLK <= 216 MHz + * + * USB OTG FS, SDMMC and RNG Clock = PLL_VCO / PLLQ + * Subject to + * The USB OTG FS requires a 48 MHz clock to work correctly. The SDMMC + * and the random number generator need a frequency lower than or equal + * to 48 MHz to work correctly. + * + * 2 <= PLLQ <= 15 + */ + +/* Highest SYSCLK with USB OTG FS clock = 48 MHz + * + * PLL_VCO = (16,000,000 / 8) * 216 = 432 MHz + * SYSCLK = 432 MHz / 2 = 216 MHz + * USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(216) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9) + +#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 8) * 216) +#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2) +#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9) + +/* Configure factors for PLLSAI clock */ + +#define CONFIG_STM32F7_PLLSAI 1 +#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(192) +#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(8) +#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(4) +#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2) + +/* Configure Dedicated Clock Configuration Register */ + +#define STM32_RCC_DCKCFGR1_PLLI2SDIVQ RCC_DCKCFGR1_PLLI2SDIVQ(1) +#define STM32_RCC_DCKCFGR1_PLLSAIDIVQ RCC_DCKCFGR1_PLLSAIDIVQ(1) +#define STM32_RCC_DCKCFGR1_PLLSAIDIVR RCC_DCKCFGR1_PLLSAIDIVR(0) +#define STM32_RCC_DCKCFGR1_SAI1SRC RCC_DCKCFGR1_SAI1SEL(0) +#define STM32_RCC_DCKCFGR1_SAI2SRC RCC_DCKCFGR1_SAI2SEL(0) +#define STM32_RCC_DCKCFGR1_TIMPRESRC 0 +#define STM32_RCC_DCKCFGR1_DFSDM1SRC 0 +#define STM32_RCC_DCKCFGR1_ADFSDM1SRC 0 + + + +/* Configure factors for PLLI2S clock */ + +#define CONFIG_STM32F7_PLLI2S 1 +#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192) +#define STM32_RCC_PLLI2SCFGR_PLLI2SP RCC_PLLI2SCFGR_PLLI2SP(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2) + +/* Configure Dedicated Clock Configuration Register 2 */ + +#define STM32_RCC_DCKCFGR2_USART1SRC RCC_DCKCFGR2_USART1SEL_APB +#define STM32_RCC_DCKCFGR2_USART2SRC RCC_DCKCFGR2_USART2SEL_APB +#define STM32_RCC_DCKCFGR2_UART4SRC RCC_DCKCFGR2_UART4SEL_APB +#define STM32_RCC_DCKCFGR2_UART5SRC RCC_DCKCFGR2_UART5SEL_APB +#define STM32_RCC_DCKCFGR2_USART6SRC RCC_DCKCFGR2_USART6SEL_APB +#define STM32_RCC_DCKCFGR2_UART7SRC RCC_DCKCFGR2_UART7SEL_APB +#define STM32_RCC_DCKCFGR2_UART8SRC RCC_DCKCFGR2_UART8SEL_APB +#define STM32_RCC_DCKCFGR2_I2C1SRC RCC_DCKCFGR2_I2C1SEL_HSI +#define STM32_RCC_DCKCFGR2_I2C2SRC RCC_DCKCFGR2_I2C2SEL_HSI +#define STM32_RCC_DCKCFGR2_I2C3SRC RCC_DCKCFGR2_I2C3SEL_HSI +#define STM32_RCC_DCKCFGR2_I2C4SRC RCC_DCKCFGR2_I2C4SEL_HSI +#define STM32_RCC_DCKCFGR2_LPTIM1SRC RCC_DCKCFGR2_LPTIM1SEL_APB +#define STM32_RCC_DCKCFGR2_CECSRC RCC_DCKCFGR2_CECSEL_HSI +#define STM32_RCC_DCKCFGR2_CK48MSRC RCC_DCKCFGR2_CK48MSEL_PLL +#define STM32_RCC_DCKCFGR2_SDMMCSRC RCC_DCKCFGR2_SDMMCSEL_48MHZ +#define STM32_RCC_DCKCFGR2_SDMMC2SRC RCC_DCKCFGR2_SDMMC2SEL_48MHZ +#define STM32_RCC_DCKCFGR2_DSISRC RCC_DCKCFGR2_DSISEL_PHY + + +/* Several prescalers allow the configuration of the two AHB buses, the + * high-speed APB (APB2) and the low-speed APB (APB1) domains. The maximum + * frequency of the two AHB buses is 216 MHz while the maximum frequency of + * the high-speed APB domains is 108 MHz. The maximum allowed frequency of + * the low-speed APB domain is 54 MHz. + */ + +/* AHB clock (HCLK) is SYSCLK (216 MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (54 MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* 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) + +/* APB2 clock (PCLK2) is HCLK/2 (108MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* 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_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* SDMMC dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(118+2)=400 KHz + */ + +/* Use the Falling edge of the SDIO_CLK clock to change the edge the + * data and commands are change on + */ + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +#define STM32_SDMMC_INIT_CLKDIV (118 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz + * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32F7_SDMMC_DMA +# define STM32_SDMMC_MMCXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz + * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz + */ +//TODO #warning "Check Freq for 24mHz" + +#ifdef CONFIG_STM32F7_SDMMC_DMA +# define STM32_SDMMC_SDXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +/* FLASH wait states + * + * --------- ---------- ----------- + * VDD MAX SYSCLK WAIT STATES + * --------- ---------- ----------- + * 1.7-2.1 V 180 MHz 8 + * 2.1-2.4 V 216 MHz 9 + * 2.4-2.7 V 216 MHz 8 + * 2.7-3.6 V 216 MHz 7 + * --------- ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 7 + +/* LED definitions ******************************************************************/ +/* The board has numerous LEDs but only three, LED_GREEN a Green LED, LED_BLUE + * a Blue LED and LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#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_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_4 /* PB9 */ +#define GPIO_UART5_RTS GPIO_UART5_RTS_1 /* PC8 */ +#define GPIO_UART5_CTS GPIO_UART5_CTS_1 /* PC9 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC 7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_2 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_1 /* PE9 */ +#define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */ + +/* UART8: has no remap + * + * GPIO_UART8_RX PE0 + * GPIO_UART8_TX PE1 + */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_2 /* PB6 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_2 /* PB4 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PI3 */ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_5 /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 /* PB2 */ +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF11 */ +#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK GPIO_SPI6_SCK_3 /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN7) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PG9 + * SDMMC2_D1 PG10 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PG12 + */ + +#define GPIO_SDMMC2_D0 GPIO_SDMMC2_D0_2 +#define GPIO_SDMMC2_D1 GPIO_SDMMC2_D1_2 +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_2 +#define GPIO_SDMMC2_D3 GPIO_SDMMC2_D3_2 + +/* The STM32 F7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 F7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PB13 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1 + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10) /* PA10 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8) /* PA8 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_SMARTAP_AIRLINK_INCLUDE_BOARD_H */ diff --git a/boards/sky-drones/smartap-airlink/nuttx-config/include/board_dma_map.h b/boards/sky-drones/smartap-airlink/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..5722e135f9 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/nuttx-config/include/board_dma_map.h @@ -0,0 +1,100 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/* +| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | +|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| +| Channel 0 | SPI3_RX_1 | SPDIFRX_DT | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | SPDIFRX_CS | SPI3_TX_2 | +| Channel 1 | I2C1_RX | I2C3_RX | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 | +| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_RX | TIM4_UP | TIM4_CH3 | +| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | - | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 | +| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 | +| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX | +| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 | +| | | | TIM3_UP | | TIM3_TRIG | | | | +| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - | +| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | | +| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX | +| Channel 8 | I2C3_TX | I2C4_RX | - | - | I2C2_TX | - | I2C4_TX | - | +| Channel 9 | - | SPI2_RX | - | - | - | - | SPI2_TX | - | +| | | | | | | | | | +| Usage | UART5_RX | SPI2_RX | SPI3_RX_2 | UART7_RX | SPI2_TX | SPI3_TX_1 | TIM4_UP | UART5_TX | + + +| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | +|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| +| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_1 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | SAI2_B_2 | +| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | | +| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | | +| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 | +| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN | +| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | SAI2_A | SPI1_TX_2 | SAI2_B | QUADSPI | +| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDMMC1_1 | - | USART1_RX_2 | SDMMC1_2 | USART1_TX | +| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 | +| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - | +| | | | | | TIM1_TRIG_2 | | | | +| | | | | | TIM1_COM | | | | +| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 | +| | | | | | | | | TIM8_TRIG | +| | | | | | | | | TIM8_COM | +| Channel 8 | DSFDM1_FLT0 | DSFDM1_FLT1 | DSFDM1_FLT2 | DSFDM1_FLT3 | DSFDM1_FLT0 | DSFDM1_FLT1 | DSFDM1_FLT2 | DSFDM1_FLT3 | +| Channel 9 | JPEG_IN | JPEG_OUT | SPI4_TX | JPEG_IN | JPEG_OUT | SPI5_RX | - | - | +| Channel 10 | SAI1_B | SAI2_B | SAI2_A | - | - | - | SAI1_A | - | +| Channel 11 | SDMMC2 | - | QUADSPI | - | - | SDMMC2 | - | - | +| | | | | | | | | | +| Usage | SDMMC2 | USART6_RX_1 | SPI1_RX_2 | SPI1_TX_1 | | TIM1_UP | | USART6_TX_2 | + */ + +// DMA1 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +// DMAMAP_UART5_RX // DMA1, Stream 0, Channel 4 (TELEM2 RX) +#define DMAMAP_SPI2_RX DMAMAP_SPI2_RX_1 // DMA1, Stream 1, Channel 9 (SPI2 RX) +#define DMAMAP_SPI3_RX DMAMAP_SPI3_RX_2 // DMA1, Stream 2, Channel 0 (SPI3 RX) +// DMAMAP_UART7_RX // DMA1, Stream 3, Channel 5 (TELEM1 RX) +#define DMAMAP_SPI2_TX DMAMAP_SPI2_TX_2 // DMA1, Stream 4, Channel 0 (SPI2 TX) +#define DMAMAP_SPI3_TX DMAMAP_SPI3_TX_1 // DMA1, Stream 5, Channel 0 (SPI3 TX) +// DMAMAP_TIM4_UP // DMA1, Stream 6, Channel 2 (DSHOT) +// DMAMAP_UART5_TX // DMA1, Stream 7, Channel 4 (TELEM2 TX) + +// DMA2 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +#define DMAMAP_SDMMC2 DMAMAP_SDMMC2_1 // DMA2, Stream 0, Channel 11 +#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1 // DMA2, Stream 1, Channel 5 (PX4IO) +#define DMAMAP_SPI1_RX DMAMAP_SPI1_RX_2 // DMA2, Stream 2, Channel 3 (SPI sensors RX) +#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI sensors TX) +// AVAILABLE // DMA2, Stream 4 +// DMAMAP_TIM1_UP // DMA2, Stream 5, Channel 6 (DSHOT) +// AVAILABLE // DMA2, Stream 6 +#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2 // DMA2, Stream 7, Channel 5 (PX4IO) diff --git a/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig b/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..1d326b2357 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig @@ -0,0 +1,289 @@ +# +# 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_ARP is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_EXEC 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/sky-drones/smartap-airlink/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32f7" +CONFIG_ARCH_CHIP_STM32F765II=y +CONFIG_ARCH_CHIP_STM32F7=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=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0037 +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU SmartAP AIRLink" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x0483 +CONFIG_CDCACM_VENDORSTR="Sky-Drones" +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_GPIO=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_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_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +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=3 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_RAMTRON=y +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0XC0A800FE +CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET=y +CONFIG_NSH_TELNET_LOGIN=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_SDMMC2_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_STM32F7_ADC1=y +CONFIG_STM32F7_ADC3=y +CONFIG_STM32F7_BBSRAM=y +CONFIG_STM32F7_BBSRAM_FILES=5 +CONFIG_STM32F7_BKPSRAM=y +CONFIG_STM32F7_DMA1=y +CONFIG_STM32F7_DMA2=y +CONFIG_STM32F7_DMACAPABLE=y +CONFIG_STM32F7_ETHMAC=y +CONFIG_STM32F7_FLOWCONTROL_BROKEN=y +CONFIG_STM32F7_I2C1=y +CONFIG_STM32F7_I2C2=y +CONFIG_STM32F7_I2C3=y +CONFIG_STM32F7_I2C4=y +CONFIG_STM32F7_I2C_DYNTIMEO=y +CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32F7_OTGFS=y +CONFIG_STM32F7_PHYADDR=0 +CONFIG_STM32F7_PHYSR=31 +CONFIG_STM32F7_PHYSR_100MBPS=0x8 +CONFIG_STM32F7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32F7_PHYSR_MODE=0x10 +CONFIG_STM32F7_PHYSR_SPEED=0x8 +CONFIG_STM32F7_PROGMEM=y +CONFIG_STM32F7_PWR=y +CONFIG_STM32F7_RTC=y +CONFIG_STM32F7_RTC_MAGIC_REG=1 +CONFIG_STM32F7_SAVE_CRASHDUMP=y +CONFIG_STM32F7_SDMMC2=y +CONFIG_STM32F7_SDMMC_DMA=y +CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32F7_SPI1=y +CONFIG_STM32F7_SPI1_DMA=y +CONFIG_STM32F7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI2=y +CONFIG_STM32F7_SPI2_DMA=y +CONFIG_STM32F7_SPI2_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI3=y +CONFIG_STM32F7_SPI3_DMA=y +CONFIG_STM32F7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI5=y +CONFIG_STM32F7_SPI6=y +CONFIG_STM32F7_SPI_DMA=y +CONFIG_STM32F7_SPI_DMATHRESHOLD=8 +CONFIG_STM32F7_TIM10=y +CONFIG_STM32F7_TIM11=y +CONFIG_STM32F7_TIM3=y +CONFIG_STM32F7_TIM9=y +CONFIG_STM32F7_UART4=y +CONFIG_STM32F7_UART5=y +CONFIG_STM32F7_UART7=y +CONFIG_STM32F7_UART8=y +CONFIG_STM32F7_USART1=y +CONFIG_STM32F7_USART2=y +CONFIG_STM32F7_USART3=y +CONFIG_STM32F7_USART6=y +CONFIG_STM32F7_USART_BREAKS=y +CONFIG_STM32F7_USART_INVERT=y +CONFIG_STM32F7_USART_SINGLEWIRE=y +CONFIG_STM32F7_USART_SWAP=y +CONFIG_STM32F7_WWDG=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=3000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_RXDMA=y +CONFIG_USART6_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" diff --git a/boards/sky-drones/smartap-airlink/nuttx-config/scripts/script.ld b/boards/sky-drones/smartap-airlink/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..8d5a78da6b --- /dev/null +++ b/boards/sky-drones/smartap-airlink/nuttx-config/scripts/script.ld @@ -0,0 +1,190 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F765IIT6 has 2048 KiB of main FLASH memory. This FLASH memory + * can be accessed from either the AXIM interface at address 0x0800:0000 or + * from the ITCM interface at address 0x0020:0000. + * + * Additional information, including the option bytes, is available at at + * FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM). + * + * In the STM32F765IIT6, 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 on ITCM at 0x0020:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x0010:0000 + * + * NuttX does not modify these option byes. On the unmodified NUCLEO-144 + * board, the BOOT0 pin is at ground so by default, the STM32F765IIT6 will + * boot from address 0x0020:0000 in ITCM FLASH. + * + * The STM32F765IIT6 also has 512 KiB of data SRAM (in addition to ITCM SRAM). + * SRAM is split up into three blocks: + * + * 1) 128 KiB of DTCM SRM beginning at address 0x2000:0000 + * 2) 368 KiB of SRAM1 beginning at address 0x2002:0000 + * 3) 16 KiB of SRAM2 beginning at address 0x2007:c000 + * + * 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. + * + * Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank) + * organization (256 bits read width) + */ + +MEMORY +{ + FLASH_ITCM (rx) : ORIGIN = 0x00208000, LENGTH = 2016K + FLASH_AXIM (rx) : ORIGIN = 0x08008000, LENGTH = 2016K + + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K +} + +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) +EXTERN(board_get_manifest) + +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_AXIM + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH_AXIM + + /* + * Construction data for parameters. + */ + __param ALIGN(4): { + __param_start = ABSOLUTE(.); + KEEP(*(__param*)) + __param_end = ABSOLUTE(.); + } > FLASH_AXIM + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH_AXIM + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH_AXIM + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > SRAM1 AT > FLASH_AXIM + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > SRAM1 + + /* 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_AXIM + + _framfuncs = LOADADDR(.ramfunc); +} diff --git a/boards/sky-drones/smartap-airlink/src/CMakeLists.txt b/boards/sky-drones/smartap-airlink/src/CMakeLists.txt new file mode 100644 index 0000000000..7afd265ecf --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/CMakeLists.txt @@ -0,0 +1,58 @@ +############################################################################ +# +# 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. +# +############################################################################ + +add_library(drivers_board + can.c + i2c.cpp + init.cpp + led.c + manifest.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c +) + +add_dependencies(drivers_board arch_board_hw_info) + +target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer +) diff --git a/boards/sky-drones/smartap-airlink/src/board_config.h b/boards/sky-drones/smartap-airlink/src/board_config.h new file mode 100644 index 0000000000..024915c055 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/board_config.h @@ -0,0 +1,406 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PC12 - nARMED - Trace Connector Pin 8 + + */ +#undef TRACE_PINS + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE +#endif + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_I2C4_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) +#define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define BOARD_NUMBER_BRICKS 1 + +#define ADC1_CH(n) (n) +#define ADC1_GPIO(n) GPIO_ADC1_IN##n +#define ADC3_CH(n) (n) +#define ADC3_GPIO(n) GPIO_ADC3_IN##n + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ ADC1_GPIO(0), \ + /* PA4 */ ADC1_GPIO(4), \ + /* PB0 */ ADC1_GPIO(8), \ + /* PB1 */ ADC1_GPIO(9), \ + /* PC0 */ ADC1_GPIO(10), \ + /* PC2 */ ADC1_GPIO(12), \ + /* PC3 */ ADC1_GPIO(13), \ + /* PF4 */ ADC3_GPIO(14), \ + /* PF5 */ ADC3_GPIO(15), \ + /* PF10 */ ADC3_GPIO(8) + +/* Define Channel numbers must match above GPIO pin IN(n)*/ + +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(0) +#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(4) +#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(8) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(9) +#define ADC_BATTERY_CURRENT_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PC2 */ ADC1_CH(12) +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC3 */ ADC1_CH(13) + +#define ADC_HW_VER_SENSE_CHANNEL /* PF4 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PF5 */ ADC3_CH(15) + + +#define ADC_CHANNELS \ + ((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL)) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL) | \ + (1 << ADC_BATTERY_VOLTAGE_CHANNEL) + + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ + +#define BOARD_HAS_HW_VERSIONING + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15) +#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14) +#define HW_INFO_INIT {'V','5','X','x', 'x',0} +#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */ +#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */ + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PC12 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#define GPIO_nARMED_INIT /* PC12 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN12) +#define GPIO_nARMED /* PC12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN12) + +#if !defined(TRACE_PINS) +# define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +# define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + +/* Define Battery 1 g Divider and A per V. */ +#define BOARD_BATTERY_V_DIV (13.653333333f) +#define BOARD_BATTERY_A_PER_V (36.367515152f) + +/* Power supply control and monitoring GPIOs */ +#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1) +#define GPIO_VDD_USB_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN9) + +#define GPIO_VDD_3V5_LTE_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_3V5_LTE_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) + + +/* Spare GPIO */ + +#define GPIO_PH11 /* PH11 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN11) + + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PH3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTH|GPIO_PIN3) + + +/* Define True logic Power Control in arch agnostic form */ +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_3V5_LTE_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V5_LTE_nEN, on_true) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, on_true) +#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2 + +/* RC Serial port */ + +#define RC_SERIAL_PORT "/dev/ttyS5" +#define RC_SERIAL_SINGLEWIRE + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 5 +#define INPUT_CAP1_CHANNEL /* T5C4 */ 4 +#define GPIO_INPUT_CAP1 /* PI0 */ GPIO_TIM5_CH4IN + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT +#define GPIO_SAFETY_SWITCH_IN /* PH4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTH|GPIO_PIN4) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +/* + * FMUv5X has a separate RC_IN + * + * GPIO PPM_IN on PI5 T8CH1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * 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_PORTI|GPIO_PIN5) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_LIB_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID BOARD_ADC_USB_CONNECTED +#define BOARD_ADC_SERVO_VALID (1) +#define BOARD_ADC_BRICK_VALID (1) //(px4_arch_gpioread(GPIO_VDD_BRICK_VALID)) + +// #define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_3V5_LTE_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_VDD_3V5_LTE_nEN, \ + GPIO_VDD_3V5_LTE_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS4_EN, \ + GPIO_PH11, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_PG6, \ + GPIO_nARMED_INIT \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 5 + + +#define PX4_I2C_BUS_MTD 4,5 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/sky-drones/smartap-airlink/src/can.c b/boards/sky-drones/smartap-airlink/src/can.c new file mode 100644 index 0000000000..1a2775d698 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/can.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 px4fmu_can.c + * + * Board-specific CAN functions. + */ + +#ifdef CONFIG_CAN + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_arch.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32F7_CAN1) && defined(CONFIG_STM32F7_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32F7_CAN2 +#endif + +#ifdef CONFIG_STM32F7_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/sky-drones/smartap-airlink/src/i2c.cpp b/boards/sky-drones/smartap-airlink/src/i2c.cpp new file mode 100644 index 0000000000..eb200ca932 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * 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 px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/sky-drones/smartap-airlink/src/init.cpp b/boards/sky-drones/smartap-airlink/src/init.cpp new file mode 100644 index 0000000000..f3ab4a92c4 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/init.cpp @@ -0,0 +1,269 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * PX4FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include + +#include +extern "C" { +#include +} +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_3V5_LTE_EN(false); + VDD_5V_HIPOWER_EN(false); + board_control_spi_sensors_power(false, 0xffff); + VDD_3V3_SENSORS4_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + board_control_spi_sensors_power(true, 0xffff); + VDD_3V5_LTE_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS4_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. + * + ************************************************************************************/ + +extern "C" __EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Power on Interfaces */ + VDD_3V5_LTE_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS4_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +#if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +#endif + + /* 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); + } + + // Power down the heater + px4_arch_configgpio(GPIO_HEATER_OUTPUT); + px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, 1); + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +#endif /* CONFIG_MMCSD */ + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + return OK; +} diff --git a/boards/sky-drones/smartap-airlink/src/led.c b/boards/sky-drones/smartap-airlink/src/led.c new file mode 100644 index 0000000000..fe722c6873 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/led.c @@ -0,0 +1,232 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu2_led.c + * + * PX4FMU 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 + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_PX4IO)) { + g_ledmap[2] = GPIO_nSAFETY_SWITCH_LED_OUT; + } + + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + stm32_configgpio(g_ledmap[l]); + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + stm32_gpiowrite(g_ledmap[led], !state); +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + return !stm32_gpioread(g_ledmap[led]); +} + +__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))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/sky-drones/smartap-airlink/src/manifest.c b/boards/sky-drones/smartap-airlink/src/manifest.c new file mode 100644 index 0000000000..2f7deac667 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/manifest.c @@ -0,0 +1,138 @@ +/**************************************************************************** + * + * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file manifest.c + * + * This module supplies the interface to the manifest of hardware that is + * optional and dependent on the HW REV and HW VER IDs + * + * The manifest allows the system to know whether a hardware option + * say for example the PX4IO is an no-pop option vs it is broken. + * + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#include "systemlib/px4_macros.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +typedef struct { + uint32_t hw_ver_rev; /* the version and revision */ + const px4_hw_mft_item_t *mft; /* The first entry */ + uint32_t entries; /* the lenght of the list */ +} px4_hw_mft_list_entry_t; + +typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry; +#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1 + +static const px4_hw_mft_item_t device_unsupported = {0, 0, 0}; + +// List of components on a specific board configuration +// The index of those components is given by the enum (px4_hw_mft_item_id_t) +// declared in board_common.h +static const px4_hw_mft_item_t hw_mft_list_v0501[] = { + { + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, +}; + + +static px4_hw_mft_list_entry_t mft_lists[] = { + {0x0501, hw_mft_list_v0501, arraySize(hw_mft_list_v0501)}, +}; + + +/************************************************************************************ + * Name: board_query_manifest + * + * Description: + * Optional returns manifest item. + * + * Input Parameters: + * manifest_id - the ID for the manifest item to retrieve + * + * Returned Value: + * 0 - item is not in manifest => assume legacy operations + * pointer to a manifest item + * + ************************************************************************************/ + +__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id) +{ + static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized; + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + uint32_t ver_rev = board_get_hw_version() << 8; + ver_rev |= board_get_hw_revision(); + + for (unsigned i = 0; i < arraySize(mft_lists); i++) { + if (mft_lists[i].hw_ver_rev == ver_rev) { + boards_manifest = &mft_lists[i]; + break; + } + } + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev); + } + } + + px4_hw_mft_item rv = &device_unsupported; + + if (boards_manifest != px4_hw_mft_list_uninitialized && + id < boards_manifest->entries) { + rv = &boards_manifest->mft[id]; + } + + return rv; +} diff --git a/boards/sky-drones/smartap-airlink/src/mtd.cpp b/boards/sky-drones/smartap-airlink/src/mtd.cpp new file mode 100644 index 0000000000..64006c84e1 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/mtd.cpp @@ -0,0 +1,104 @@ +/**************************************************************************** + * + * Copyright (C) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 512 X 64 + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(3, 0x51) +}; + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 2, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = 32 + }, + { + .type = MTD_WAYPOINTS, + .path = "/fs/mtd_waypoints", + .nblocks = 32 + + } + }, +}; + +static const px4_mtd_entry_t base_eeprom = { + .device = &i2c3, + .npart = 2, + .partd = { + { + .type = MTD_MFT, + .path = "/fs/mtd_mft", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + + } + }, +}; + + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 2, + .entries = { + &fmum_fram, + &base_eeprom, + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = &mtd_mft +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/sky-drones/smartap-airlink/src/sdio.c b/boards/sky-drones/smartap-airlink/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/sky-drones/smartap-airlink/src/spi.cpp b/boards/sky-drones/smartap-airlink/src/spi.cpp new file mode 100644 index 0000000000..a0e3e32aed --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/spi.cpp @@ -0,0 +1,60 @@ +/**************************************************************************** + * + * Copyright (C) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#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::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortH, GPIO::Pin12}), + }, {GPIO::PortD, GPIO::Pin15}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // initSPIDevice(DRV_MAG_DEVTYPE_BMM150, SPI::CS{GPIO::PortH, GPIO::Pin15}, SPI::DRDY{GPIO::PortF, GPIO::Pin3}), + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/sky-drones/smartap-airlink/src/timer_config.cpp b/boards/sky-drones/smartap-airlink/src/timer_config.cpp new file mode 100644 index 0000000000..52cce68b94 --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/timer_config.cpp @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * 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 + +/* Timer allocation + * + * TIM1_CH4 T FMU_CH1 + * TIM1_CH3 T FMU_CH2 + * TIM1_CH2 T FMU_CH3 + * TIM1_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM5_CH4 T FMU_CAP1 < Capture + * TIM5_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM5_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + * TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index2, DMA::Stream5, DMA::Channel6}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer5), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}), + 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::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/sky-drones/smartap-airlink/src/usb.c b/boards/sky-drones/smartap-airlink/src/usb.c new file mode 100644 index 0000000000..20d223245c --- /dev/null +++ b/boards/sky-drones/smartap-airlink/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32F7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +}