From 0ce76679b7e4f5104886a64ae3a906f1c0e249da Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Thu, 15 Sep 2022 11:13:49 -0600 Subject: [PATCH] boards: add new ARKV6X (#20191) --- .ci/Jenkinsfile-compile | 2 + .github/workflows/compile_nuttx.yml | 1 + .vscode/cmake-variants.yaml | 10 + Makefile | 3 +- Tools/upload.sh | 2 +- boards/ark/fmu-v6x/bootloader.px4board | 3 + boards/ark/fmu-v6x/default.px4board | 89 +++ .../fmu-v6x/extras/ark_fmu-v6x_bootloader.bin | Bin 0 -> 45172 bytes .../ark/fmu-v6x/extras/px4_io-v2_default.bin | Bin 0 -> 39924 bytes boards/ark/fmu-v6x/firmware.prototype | 13 + boards/ark/fmu-v6x/init/rc.board_defaults | 21 + boards/ark/fmu-v6x/init/rc.board_sensors | 71 +++ boards/ark/fmu-v6x/nuttx-config/Kconfig | 17 + .../fmu-v6x/nuttx-config/bootloader/defconfig | 96 +++ .../ark/fmu-v6x/nuttx-config/include/board.h | 558 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 87 +++ boards/ark/fmu-v6x/nuttx-config/nsh/defconfig | 295 +++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++ .../fmu-v6x/nuttx-config/scripts/script.ld | 229 +++++++ boards/ark/fmu-v6x/src/CMakeLists.txt | 71 +++ boards/ark/fmu-v6x/src/board_config.h | 524 ++++++++++++++++ boards/ark/fmu-v6x/src/bootloader_main.c | 75 +++ boards/ark/fmu-v6x/src/can.c | 142 +++++ boards/ark/fmu-v6x/src/hw_config.h | 128 ++++ boards/ark/fmu-v6x/src/i2c.cpp | 41 ++ boards/ark/fmu-v6x/src/init.c | 282 +++++++++ boards/ark/fmu-v6x/src/led.c | 235 ++++++++ boards/ark/fmu-v6x/src/manifest.c | 223 +++++++ boards/ark/fmu-v6x/src/mtd.cpp | 128 ++++ boards/ark/fmu-v6x/src/sdio.c | 177 ++++++ boards/ark/fmu-v6x/src/spi.cpp | 86 +++ boards/ark/fmu-v6x/src/timer_config.cpp | 80 +++ boards/ark/fmu-v6x/src/usb.c | 105 ++++ 33 files changed, 4007 insertions(+), 2 deletions(-) create mode 100644 boards/ark/fmu-v6x/bootloader.px4board create mode 100644 boards/ark/fmu-v6x/default.px4board create mode 100755 boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin create mode 100755 boards/ark/fmu-v6x/extras/px4_io-v2_default.bin create mode 100644 boards/ark/fmu-v6x/firmware.prototype create mode 100644 boards/ark/fmu-v6x/init/rc.board_defaults create mode 100644 boards/ark/fmu-v6x/init/rc.board_sensors create mode 100644 boards/ark/fmu-v6x/nuttx-config/Kconfig create mode 100644 boards/ark/fmu-v6x/nuttx-config/bootloader/defconfig create mode 100644 boards/ark/fmu-v6x/nuttx-config/include/board.h create mode 100644 boards/ark/fmu-v6x/nuttx-config/include/board_dma_map.h create mode 100644 boards/ark/fmu-v6x/nuttx-config/nsh/defconfig create mode 100644 boards/ark/fmu-v6x/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/ark/fmu-v6x/nuttx-config/scripts/script.ld create mode 100644 boards/ark/fmu-v6x/src/CMakeLists.txt create mode 100644 boards/ark/fmu-v6x/src/board_config.h create mode 100644 boards/ark/fmu-v6x/src/bootloader_main.c create mode 100644 boards/ark/fmu-v6x/src/can.c create mode 100644 boards/ark/fmu-v6x/src/hw_config.h create mode 100644 boards/ark/fmu-v6x/src/i2c.cpp create mode 100644 boards/ark/fmu-v6x/src/init.c create mode 100644 boards/ark/fmu-v6x/src/led.c create mode 100644 boards/ark/fmu-v6x/src/manifest.c create mode 100644 boards/ark/fmu-v6x/src/mtd.cpp create mode 100644 boards/ark/fmu-v6x/src/sdio.c create mode 100644 boards/ark/fmu-v6x/src/spi.cpp create mode 100644 boards/ark/fmu-v6x/src/timer_config.cpp create mode 100644 boards/ark/fmu-v6x/src/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 4e61920c58..5401956ecd 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -42,6 +42,8 @@ pipeline { "ark_can-gps_default", "ark_can-rtk-gps_canbootloader", "ark_can-rtk-gps_default", + "ark_fmu-v6x_bootloader", + "ark_fmu-v6x_default", "atl_mantis-edu_default", "av_x-v1_default", "bitcraze_crazyflie_default", diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml index 16351fb82c..2b7828cc5d 100644 --- a/.github/workflows/compile_nuttx.yml +++ b/.github/workflows/compile_nuttx.yml @@ -21,6 +21,7 @@ jobs: ark_can-gps, ark_can-rtk-gps, ark_cannode, + ark_fmu-v6x, atl_mantis-edu, av_x-v1, bitcraze_crazyflie, diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index d114782ddf..e074000428 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -131,6 +131,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_cannode_canbootloader + ark_fmu-v6x_bootloader: + short: ark_fmu-v6x_bootloader + buildType: MinSizeRel + settings: + CONFIG: ark_fmu-v6x_bootloader + ark_fmu-v6x_default: + short: ark_fmu-v6x_default + buildType: MinSizeRel + settings: + CONFIG: ark_fmu-v6x_default atl_mantis-edu_default: short: atl_mantis-edu buildType: MinSizeRel diff --git a/Makefile b/Makefile index 5d5943dde7..856e7bb883 100644 --- a/Makefile +++ b/Makefile @@ -320,6 +320,7 @@ px4io_update: @$(MAKE) --no-print-directory px4_io-v2_default @$(MAKE) --no-print-directory cubepilot_io-v2_default # px4_io-v2_default + cp build/px4_io-v2_default/px4_io-v2_default.bin boards/ark/fmu-v6x/extras/px4_io-v2_default.bin cp build/px4_io-v2_default/px4_io-v2_default.bin boards/holybro/durandal-v1/extras/px4_io-v2_default.bin cp build/px4_io-v2_default/px4_io-v2_default.bin boards/holybro/pix32v5/extras/px4_io-v2_default.bin cp build/px4_io-v2_default/px4_io-v2_default.bin boards/mro/x21/extras/px4_io-v2_default.bin @@ -336,7 +337,7 @@ px4io_update: cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin git status -bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader holybro_kakuteh7_bootloader matek_h743_bootloader matek_h743-mini_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6c_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader +bootloaders_update: ark_fmu-v6x_bootloader cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader holybro_kakuteh7_bootloader matek_h743_bootloader matek_h743-mini_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6c_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader git status .PHONY: coverity_scan diff --git a/Tools/upload.sh b/Tools/upload.sh index fe466da36b..25d41e389f 100755 --- a/Tools/upload.sh +++ b/Tools/upload.sh @@ -15,7 +15,7 @@ SERIAL_PORTS="/dev/tty.usbmodemPX*,/dev/tty.usbmodem*" fi if [ $SYSTYPE = "Linux" ]; then -SERIAL_PORTS="/dev/serial/by-id/*_PX4_*,/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/usb-The_Autopilot*,/dev/serial/by-id/usb-Bitcraze*,/dev/serial/by-id/pci-Bitcraze*,/dev/serial/by-id/usb-Gumstix*,/dev/serial/by-id/usb-UVify*,/dev/serial/by-id/usb-ArduPilot*," +SERIAL_PORTS="/dev/serial/by-id/*_PX4_*,/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/usb-The_Autopilot*,/dev/serial/by-id/usb-Bitcraze*,/dev/serial/by-id/pci-Bitcraze*,/dev/serial/by-id/usb-Gumstix*,/dev/serial/by-id/usb-UVify*,/dev/serial/by-id/usb-ArduPilot*,/dev/serial/by-id/ARK*," fi if [[ $SYSTYPE = *"CYGWIN"* ]]; then diff --git a/boards/ark/fmu-v6x/bootloader.px4board b/boards/ark/fmu-v6x/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/ark/fmu-v6x/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board new file mode 100644 index 0000000000..9068b52bd9 --- /dev/null +++ b/boards/ark/fmu-v6x/default.px4board @@ -0,0 +1,89 @@ +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_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BAROMETER_MS5611=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_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=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_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_SIMULATION_PWM_OUT_SIM=y +CONFIG_MODULES_SIMULATION_SIMULATOR_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_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin b/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..cdf31e487d31ca35d180d2339648cffed0d9e229 GIT binary patch literal 45172 zcmeFZdwf*Y*+07WWoC9VAv3uElM7@n0dfN;31|c@!_2UA88lpMUj$nRg1S?vL_r&s zh6zDMsTBydK(wXAwkTdQf%FhCCW>0E`o1$j`UWB;6?Gs%-9r*)=Q`)RX27;;&*yjk zJAa({eAeu>_g;IgXFcm#&w6faO;014(>Nl$#Qy*3|Hr}qcW8iI`-LyRz3a!nP`&$g zzsfUJ=5?&^>;9P9XT+b1Y*1pq?oX(j`KA8pnU_Y(E5&uEPU zdr{VTFY9A>UW_A*WV#ebOke6_O_yX{)5X#99hdb_b3I<dGj~DBW(q;S`b6hQ97ku5-vdSJ$7sEv+m`IxzUR z2Q9MA@wW0xev;%EsN#~`ME>zmdw=<}?fvVYO+p!q%;4#=$aR_f`WqrI93^t>Fp=*V zbtrt=`+=njuSHJ#exS%eGCds01WGdFUL}Hr{Oqqu&km$JU0a$`CG&vCY#;Cxq`H4p z#_VGDksQ+hI}g)9a&7&4Jxj}$m7?8&stSv&;~cVp_O-b0sc^_PPJ2B+;Hl8MDSTBZ zV?&wxZ}RnShs#-(HE-W)M_FoxqikOVJ4gyr*VxO>u1=Ng^1-F4?o??PGuoLd>G3}s z{oG4NJLlo*kkzQ`W*5p0*zA#V{AlNmrLocuT<73wmsvK}Jv)+PkV8#)lkYN{Q{7g4 zXO=arUFKN&Eh`tXhMZx4Zb@Dlhd$VrIR?lwj>0`)+kpIrB=>Yziewt-S+HQhvn0hG z$(xYRPjM$mCK=CV&yoZ;sA0gCuwZ~BF!cF=Ek6PEn`ImN!ZuYEr%F4y`GY@xo!Q6C zy(2)J>~iIXoy34^I#L!=qRmF;v7F`xmSMID?If;*U2Z_)kp}QSk0;BCku23Ce+SZX zq{T>}Cl_NPMv6HGy-F`jK++?nNU^r`QoF3j(=W;z z^>{BKVI~jxE~HP8dXT~l(O<;1syKYvdIa-qE3tUYU-#?l9{lqb%#6Bz{WeOw6J3+a z(xilK+<@nyYA=(Y;7Q!}koTCESm@i&nzy3tAun&VzJYmgwA9Po{AGaTeC=}#cs8iZ zlH81?H$Y|vd=}iZxc@X@eWR)vFan2k?xE!^XxS8Px%OJi>QYL-o()p6Zq{}Yv;9iWk~LWg$i-$E@Gl&v6oZ-9u-(p{+dued z)ujN_z!Wm|gMsK%=G>a1&#yhZ8hLhj@czwAcWlwQe=GTuT;?28^tW$HzPf=S*Lj56 zMKB|PHECt8BTk_BC59;}hyx32;pxeO>u5xIBXKt7uNOlur zde8hkp(}lnwJ6;g7kN%(z57bw?mWKBuxN4QX@6id?j|m(irife{5p?4Q!a?0r=l``-p$CYjUY!QHr}<#w=cCa_?QW zjG0&#?cExO9sIH$r4oRjgi@_B6(jzKVPe*maz-NWAGUyxZFV^19*4y(Tj+?c{<9u5 zz@u#sg$Zzgw+iX>`Wfk=wDId0B0PYU)Z(!)FIS4Z7!EB78(VdG=Pr?a_FRgaZPK@4 ze)iHCtOSx;$T#I~{ho5Mj#T$hpsHA)G*?HyGnbw;F(pJU8dCm9gb(j$a`i27qTpk5 zV|{6@r_I88BAXRr)VIa1=Uud>=re<|di~V^h4=b8X*j>_{Kx8#AKr8-?$ntrXA<*> zDpr@AGS!kr+F$P{9@4@bAu_KpZ;-a=J)h(5CNdYls=qG&QP-)9@iKjWJtZj2Jc4u} z$guw@Kl75Dk(HzA_Fhyn_9Gn#X0cg0p|j_e=l@aOyG#4`i&}Y!!q2lIO~-0$Ap4O_ z$Q2=1MADI~My{GnMovLaA&E4{AjeFgISx5apg9e48oFjHI^=Y17v&5VYXivv18%zx zAv5Jpy8a9og}=NveG%&X zFp9H}&(i+zIlt+q_`2Q}y&eei?6JW0{{26V2A>nYTKzixo{k$}wOp?!I*vSxxk!AV z?H(kdg^>@9FqkL5#lO%(X1Cm`Yx9G<=yUVdREmq&+5%C3Ia_ zb~|Gsnage~tSTQk^59aJYVgJCx|Sv7CNWFA#l6X$?!L=?yX&9-w?*>Ne_qxPaTbHQ ztkfnRdbrH>O6|Ls_(HYiP#rJdF;wij8Ff6axEH*utjRxdiEQQMKZNZr<|Rp-;$|%i z78O=8@|l&iDXW2 zr%BUGp7&&L#;P!qi5^`UF__G_zBhVEYLGa02Ik@7kwX$=PJJNTmG0pzg;g5)rlA=w zt(VA;jZDWCco>?7t46+SJTvnAgD@k%I>K9YC52T)UOJ-2Tqg1{MTM`4yhy>?qcCz{ zbTnX*R+2vj7AOT(DH7B7Hp3MBUg0}l0e=)UBy$JmavZJ(q&%eANSR2Anq=z#M1))8 zh_DT1jCjT)B_k1}>}2pOBN0ZPBEq?J%D2E1LK$I|t9+nn^%@h|&7)ucs~APfw@7>T zej?n3`e->?hO8dHR_5>DlsPkj2&+)$4_Q?$Dltw>?E>$50=(;6t8sd3IJ9=mENT`B zC0Cnm${ZW%dzaYVPk_^cirUu86Uhkr=Zz=AEr9h8Swc%(S4`Pb#cEyYW&1kVrP7{a zHDnefDxsKFuB(Amk$ywVQ(Vyg((nHh|11Rm42SlNuLHa)m%b%k%EKtl9?`d6*v=GQ zsH41-)>G7y>`IqD!n^4sO|9t95YyGmB$_B(()W*zf zXhv=Tj8gw&Sr_6ylliMs++3Xvc#65I2(~0hpqTQahS*WWwdCXXLqZg|M(J_og~JJtSKDoh`dQ^;jcX<=5VMlOhrT${|=53-% z+$rXZ8R9u5Yd?|S8RDlpyR$^K%&D;=4D(Zqx_|CnD$<$9fX?};1>FV{&EGt-t(C%) z)l(qG1`P~-HiWOgK6_{_cQ`*%zHvCM=a5t?>dWXH$`Z8=(a|5k|YYBOrHzKnXGcfO+V#sjtVTeg8SzMvEt zEvvW&y7IiB@cN2XjoVERTjUems)w`1BnKaKvW<0^^XSzd9%kf@p>XKPxVhAbJ}(&K zEsYO{L&wImL>2AvvrGYFO>F*SV6H@hd>pt|%~CSgP0W);LE2*1b>ArxV`BMSNyumW zPCnSww_2y|UXGe>8h&3Pi?;+8f|uke1wBl`7pQ}=<`3~7F>{wF!Yy&VEUW5!I}Ro2 z(>&UXvjNICD1Is5p!{RDYv!d;Imu3L-zM%6H6qEJC@v5UW-|C<6(>J4ZWEsbC+1|& zxR}21c%I14E)vy!TNy^q8&+er+Zsc%96r()6Z=w7h&e3sw{~C=w*kWY#(B}}Tp%*D z7vpaE_#MtO3se2XSf=oCe^J(~;v)UGU13sws6f5V^7}aXwsFS#*jlyoxAsXVnc0gL z2L0=0HMtaUDSY`46+Qzi(oRmEJMIygy+%<8G6E;(jys)x%$XIWlg=D+GO!hVK!07n z{}#!w7Oawx8GCALC<1y1%HBg5UXOG z!dSQ2zxFdmCBT5DIeEjV5}@;+7oi2TeAdjlOrk*|^8a8?GxDz#`cB`%i_5(p$%ysi z_sV|AxGO*xZ5Q=6PX1vlg+T?b@dR*vFXl#(ceas}R}JlVXSEtJ<9ouiN2(siOiY}7 z&nPjz;x1}y8j3U4NzfrZjCsWaRmDXuTP2k^+gtGnlgpoB=2bjEEQe5z_UxV^K4>Ir znIEV0cP}6dhg!m41t?sA%Bq(8$D;5M`OnAy`Sjv9PY)d@7Im4rBt>Kj|CswWR$VqI zu!=t%GC>}oJeu<6D%7|5Fd!p6Ud&diw|z^q(z(d=G>MtV*(Q{zq=ibMn@FVZ1P7Y0 z+H*~dYh0V;rMP<(>rgmUAEq$BjX7A=c746Gdbw?BJaZa4jfYApbbYBR*0+R1SHhI1 zuCa5nZ=pw?M09 zXC?T!S;;r7ItgJk}6O?O1YBys|@@N=U^QE4+tKV3(q|E~jP=}S=EME>%% zwZP!AwoH*8Z^9fOUAK;Mw}YdfId~hlI})KVu!Rxq>22n`l}@LcNyG2T_V z(QAI>X}j9b1(O+Ts{kyXALe_EVx|-faPo!W=$d8}i`w)p++%fgE!_HT4L`n=lV2RZ zK3CY>I6p1*-4#<++8bbUzw}d@X63$i(*DahlDQR$(l(PxB|=Uv8!@&rvyFKne{^Ju zK>3(A!9^(hqQ7g(6ymKi5Yc7%9qmWtUACJm`=ofL3Qa>NgYE8xn zbMk}3hE`gxdgMwV9QsXoAb_=F!2~g;nisPVJFOg6Y9>n~)=>DV1oJJ9&{%V|S)H5c z&#vZ!C6FHnhuz*>aD@x^td%VH5=-M6BA*OL?i-3gn$_vo8(BFoOtKn%m@6AT25uf0 z$*$fH{`A<0TC^RuNm+-9{NxD9a``r({bp&4yI*Qh^QW_`8OwHClB3R@E1dvb+^X+y zkq<6nXq!8uZB7q|ZXZF(ZQsRlDpo)6zwyQzHTdbbv1cEOVP!0+o8fEu+!rxj;Yi{$E6 zsqR@rzuF+FgK-SE&-&P&V%iG3kIFN2#?p2oTxZt;@xXSgXhus1>Q=A&p>0dAmYryO zyjP1lFs9%DQ63Zy{m+;ceg509avL~S{|2Hz`B=8OOslAN~E+Zm`?7J-iYv!?~Xiui@oRp?`8G(oWmOcsZVc{-(dJTxMg^Z`_ZuvjW%YLu;iC-W#f!mx%deC2mI% zl@^Pjm&(;cH;c4HP+?{ZbF_KAkUJuyS4Zp9x72Ot#WdB#({o!rQkK_&b(8gH0V~N^ zn~AKAtUh;uSBFEdj5ThD#jT>TP7huQjwKuMmSUR7&mBb{YQNj(y6qn{C&@gk_Bmud zS64?@7m7oA)r(cdnN}iOj%iw0tia4JR{lj8_M?4_$pCpgVH_5GiyE?sTGo!!=V}v+ zylR{nqtqL|Okn4m(v7w$2l|#i7VFZMrb#i8b(ZNn!58l{?Vwb;pcI=uzG?|@fHncpk*t8{2v{mqBf0*$VW#)kS6f`_pA*>o-=lR z1^Iq>>oB*~erBC^8&jCpto0BJwiuN=6}#fEf(}o=V@g^1)SJ=#%u9-6qIgqT23ES03h~5?U5c=SJ45B8wu?&Lg4UbG z5>W3iAYa_mI_Wqu_6JDrfL{yCNzfM#jg674FEJ}`7Hy#V%VSo|bH@DcC1PPAOMVf^ z^HxZ??nY^?`+{^efalIv+}(jW5;HTwp98&-e)aX3N_@PPz>5BIn?NR95p(gpXy zh+N+gk+o^RiRGr2EfPbu!pFZ&|94d8UDMc^Jsc!0(<975R{nB4Q@R5AVFGNqHt%@o za`-bT*=yN!$jb5l#=ZF#WyBmi>bI0HUuZPOv2Iu3m< zsZuPz8dvoywE1Tg*2esrmn(;usr=bey9Q;1@h<{uT&aHaDR|=Zfa@Y))gC0mjYtn6 z@vsAN?h`@%GH#Gqv~CLj0BrRg{alie8{4IZHOpcwfQF|dj3vd(!IQgV6|@rTP@oCl z)47SVlX+3Nfn4!>DqYKz8L%|KD&ipnHmp}V_2EHs1Cd|#93HgcdI(p~4L12DPe(t2 zedn)X27LbeBu+NlChzei4^)-E)6d@#Z0Wu4$^|6@?#3dKyL(bzy1E2@3+u4W4_a7M-1A_LrKSylBrCVs|)p2pr-XDsL!^( z*w;AdS@%hhaE`t>u2T^@C>%^yd~aNQxy-~-DC36JqlX}Y7Iy7d<##%I<2WXJtvktg zL6y+S%W?dliO$3ao1AJnPJLPtW_xX#Vf9sb@VKdtcNAewR0=0X$^lu^j{}@(Wq_FO z43x_xt|mZ?zX>qLUkBi?46v5A0B1QKu%L~PBDDWmWb8VcVM%QdUyhD-e3wAS+Pch} zS{WT}I@Wr7a=QU`8qftz?R3l`f63Y7ygUPG+PEGRv>~c411^Ct(17x zD48aa+>1U6wP4f8)7x3sK*Y~O?Vwb)3$)@#^dR?UbVb( zgm-+_yvVCvqz-N*CMh43nWW@O8w)LNu1RjomNw=`tS^vZj<){OhDm)%wRXYB7cs%p z9J~m*+wJh%+%V*)Yw-lJZY?h+h?+UmWQ}TjYqltW+i^qtEB3G51RNw|OBN-XbOT3jew8t*G=qkMp+l6H}yoyvH$-KrKX_>o%v z&2Wh~=5`)qkS}F>sSlBkL7}?}BhYrS%C<3|$jZ?u{^@rS>&sfBw{d$n&vat_Q5v_y z(+y107UK&mDjapzp~X@f3HhA zb+2F9W=*;;$@LbVcq}gJMcwcgp3%~XDQNd8igCfcTkhSm{_T5x%BYdOPbllaGmm-8 zeJJ~22cFTgl&hFGR#5PtH!VUSS#)~icx*%yYewB zhlf<|#`~Fr=K2fwv-OtsmU?2TxEDHG#Aa61qRFSUW&)i(=A|?gf9Ay69Fagm#(FvO z=~_qLYDsB(7)q<=lFN=U-U2duWG4V zOXCKTMT?i&%*Y%Q4$TSYIkUt}S;MbNd+$>G4<7)Ha}kSFRq=^*3oL|7yo}Q%bEG3x zRc6H1;H94pd18_9<+%Po%kBa+2;Y*D9_9r{?r zq%ee)8I|BZrEEp|Wz_=$(^t%RN3I6fWG^_w! zePFuxl=8frzVkd#>&|iD8|!DysctIu$Zc=++gX#WV{CvVhL4F$aI^;4Y@r=(tUeJq z3`o3#J?n8VdzQX~HFo?`_-n`gb;=QaRk7oKTG!syRmIoyU6mdE9e6`$gYEuiJMT*jc|Wab1#g^*Y#ta=!ANjtL<6bhpY7^focEtrn$Uwk!uEXB+5szVojuN%k$YNs!|1zy-9rIo}YDBU^ zhJwyUt$shQq*BdZ`?~v8KJQ@d<{aO8*+4J{a>{+Xl^QE|n8`(4#shKf<%o!ayyDoc zc=URa+W2iIVxsr8dU}UdZ~?t{$X2f2eOlS7XXQT)!;cb35ibPnhwCLywldaii=X7O zXHP57>x14T)NJr24Uo;r?F@8-t!S}c(u*hhJxN;?5Axl*txBzxl@AQRqiiKvSec#~ zKOI0heQ#u4eF@s4^Zwn+HZm5vJxt6rmk`mY$3yS87GZqVr8(lS@pL@Y0h_p?mFCAn ziy~6`v|OscJMK>w>(NTCm%G2A((EOsJ;fH$0DCWE8j92(#jP@Y9k+&5%ActYze_n{ zO%@BidO+42*2CV+%dfy{v%`3*vH^N~yzWKiQ7hw%wA|ubqdD)w3YAWGwW{G1@O0*EazXW2cqfBpiAU^tK1rUAR6^1guNX zAomJnnkdfh0L~~~A|4Uc*JM4d?2o*ovrWW1dL132?_RWm>Z*y2#)?^6m`9#$Qi;y{ zNp^`Jty)vu5r~Wq*S;u3_62~*0f;CR51}Rs#RIrTp;(994kM-2W$5QGmc@8scUiU! z{zUq`kVd!JXdh^qU+58^h!{rNe@E|vih6fAwBlM{9Wq(wkf)%(!~(2Y8PMn^+6!{f zi+Qag^0Fc7PXYX(PDVZ!rYk=q`@^W4c<@HBj)lG+1x|#oiC-_kO~W`;~;#cW+X7W$u2#$px)@BoU-=P~Zl`F|Z>+?(M-qGHHk z4iPrDXiFumZ0{+=5_4O+2v1kq&EB7+TMH%e86^gGsnz3!@S_QNK|c@fbsF+z4-$>T z(6`v7xXcCBNm53(Mb6-Mw+p5?Q<8hW`9$?To1>a5;baZRk8s>d>933RZ5@asEo#{x zOyktKnO)t@j5#hdt(4E@N7yT~+sQP3+P1q4PJ@f zN#c6}3Imp_Ou6N0$thW+ziUQMJF4erzE>SLBO^D`=CFDo^>*}STHG|v2v@OEy1Y0} za!Aj+ostU{fjc;^Gp^F&#Mi4FQcUHYZWg+VQ!+(jIkkxOVh4IQE|884dN#W%E%I^B z(C$EAT&rx7s+5ybY`iPUrgd;`89bT7lR=Wkd%^>ZzNO<5o47y{773EkZbOWw2Helk z9%m8SlPyUOts9&e_vx0a0mAUaAuX3Y%~i#)Q5GjGBGVJf%jI<8_hPdc)29YUB>T+<#f=B4qn|a$ zSxluM=a!EQAKrBj^*U@N(>*i5AD(#d&(ym71nglcw@-1tU}rypY+b17$zUcc>JF-z zW%!wCgFlSg#O_K@_30MzeOyvpCdNA9m(oV>kE=VHpRQ*6I@x=qlg&HHLd6UlAv5TC zaFw)pu|bsEn8K6Lj)t&iUmr7Ti?ce;l<49Sm&=T>1v{lx-umj>B(Co?r0wqJeW=A^ zV+TDO%B1HPN96nONH)X_3aN@lSJHa*M;z7ZnS9wbYO_#zvq3TxQyf$saaN~K=Wj!M zyn2Mc<1^_+vFZ(XuY?2UB)xd9*xgGI5cbm=VsBR%w9TO6w_Vf!tLIkC4|@ z$*tmA9jl1NwW^}VSaYJkLuG93k;o=@{|T<*;Sb^aDXZO6Tv2mR!u4z08xVkVWMdzGn8}BykOsT>kl;v-pXp zU*i&QFKJ&Wd+wQKD|9$|YaNVS&NyVxGVnRag(Z%fw>=iQoJ(;mc$ljpMxm4o>RHAT zC)L|5pgXzEBwED3VJwJNuo0y{oGu8qo|YYop(E+`^4>+0+wRQeC!apV>0Qxwa^b`I zrk&njf{dbV9sjqsNDX6AmDSmZF&aPI(?()w{e`2ne%B+hk9<&V@8!&n8Y&TYtC`Ml z=$-a(=vVCvYS@|&)#bhR#6|6bE5`MdCdo;omPuksMAl1nJ8ISghmMD%dU2#)z|P1J zuCH5+zvU%<(lEa11Ft&U+yxujFcZwT`Mu1vSH!qsRey^8xA2!v?~PY~);zwE%AV<# zwGOk_U1)I1ZTaG*05`a61HAKdG&8^ON9mpzgOCS0yscFGruK3~71OnqeoZ}gu9_H7 z07)`9sn6@JOl0)w5opr$8Ds&L2a;Af7_R+L45AbUW?3P z^*Iss8l$WO_uv-oJn9fyY%=`uE_Im!(dkbCo6Ou{KW7{ZeS|eaXwwtHW}CnfJt7Kd zM3fqF;UD}MQ40sEo*+8Bj+$;r8>Geqt>vSzr7{g((Qv3cJQTGi(wC|`uo_@4KvJ;C9tT%I z+uEgXTteqv8pj3kY>=^Ru`_)hp8W)TF!R3ynTW1QcMo73^>lt9QP`E1_(~0;3x3k7 zt+}CeC9`6=T_&qnEUu`zw|@(`iPF};Ev?m6Lw8lU9xixlaNEmv;Z#Mx zMxAhWVi{x6OWSQ6F!e!Tiuh%q@TnXz9~>;j84leSreE@a!ct>teQcA;yt-eL^w`FN zr~0=|biUer$Udj`wXTYq73xE$k5ayZJ{gc^qhHn*PSh?+osyQi*G@jMwppYT{hDd4 z!r#Iw++D~oM5zmw8zfu8vcaF$J2MwNJ4Yv zidIWaYRO6_W%&Y`tV#i{R!4AE)#l%p5{Y}s8tV&O*p_(vim3@sbB%YTKe&`}IdIrH=d?&fqp0rrMg(Ls-;8Pe%;Uh zEncv!CJFmvrudU9U8`@u$APKNDsBpDfFAZa+mFkjgfip8$+B~4P(|y zTWpqImeacF%%-!yZ!8KomDRq#rEus^VYVizG}idqb=FH_`u+T z2k9;ZPeqd3T*FChP|q;trz7og?)PZl>D)k~>j%ZXfJDqxpHC3o)^I3oykZj{8J~)c zQJ*z=lfDgy?ga#~#@JE{0cNPfF+h@*EglX1AgnGU&|{*l(y6PLSl@$u+j2R%!qohNJL!UemZKn9$;<^hvLUn!D>!5 z`20hf;5)?Pr0=FVg`iPbQJsF1Szg4hs0xQhM%O-~nPrg|acdtqi#-!Gf`*uqOHyI+ zV-i=mwHE9@bHj3a%Tguz7R$hRg&kL$+46LBZy3*6wy+kMQ`JkK7J7x!sJ=m?>nt$&v zs4T$jnIyYmA-FYvxAKUUKG}*Zpa7oAd%0zZS%*AiTV~m!^6|lm5!#(U;_PXx*{!7a z>{cds%&1va^J&eZUd@aJy_{*cGHHjsH{Prpep1mk>xQ?Cw+7>MSzWp-eC!G(TTYor zgiA;_AT78hdcA<_v|FQTCax}|-_MPvn^11IqVGt@en6Fv&Efo$WRH&cG7evt@+_OW zHIq7bL$k~hcSSiqB%T$EX@4kP(*7V0Y5aQmaA@Z!)kJ?{jmEgD4)9&Ka()w0)VD|?7mjry$^%PJ$*4_zc$&^-QlfXv!FQ1m*3Z|1ztiL3khB+JI@ z_0Au7@O6^2d0_qP(Yg~+_YeHhn&(EKkB5v{NB*_utZ{$f-s8*-oZlwviE-m!1MCf% z{scL!Gx=j;8#ggG^V!K==PyFy)K1VP5C+_W;~FVr@1LTzJj=v;jR7TpT!aa=T-I-2i@uRyx0k z@+EkUY$I|QVT$1}jmq6#`b$?Fyg}Q`xL%&5+o&x!){Tfl&onN+^GVl}WmBX?X`*dr z9Q72!Q)}8Xba;njgK70|;s;soMGS-_d?kF~?VmluweLupz(keMG^nKIMN=8GYRjuZ zBB|hUJQ`H%e)x%MKu(H!GB?&nJ(<72)pJ9M|K0xBiDahJ_Y+t8boGdE<6iM^%IpUS ze4J&q&ndV3{ur=slWnzsQ}P~o3?n3SdcaszYnz!XYJyY9!FHP^W4LaF)ZYpI(lkOE zE~bV-xOSf<%!k#@SL;3bLTz}w7 zw`1pRZ8$UoUhs%N?Ab02)2Wvd+$#lR!HNKxeqQPDoL9Q`gI70wt+}ZaKGT#t6`|@Z zyvZ3hMU&RaSSHC~QmP2n1|`9o3%Zv%cdpJq1N`$JqYY>WQUs$x^yaUIX^B;kz_#Ps zs$n}>3;k}cM%zi>T!(i#;Qi5<5PA1AK^ zKXakiJJX~|*afpfiK$|Tg)0SivWr?!JY0rtGB`C;e~XVaAZl+k-88+IQ{U~H>Siou zuvPuU#f-$|8^jfx-1&4SmHSy)W*6tg0|S-A|K+Mz9x)~YBWm2MhL^ckK&R3quGpBe zX`4E+^SrX?t@Zs26ZUQTL?Q5d=;AT6S;Wc`TW`GnBRoslxNqZJ;7*9NHUev`y@d2> z!TshA>m$#Kpnot8u2#}8uY|%@$jUWkmMqQrYOgzeu}HFsXtQNjS88_}4=dv9BbyJ7;rW&9YwBqVlcXM7f$K zY3;_=FV=2i%}St=-#n;#O^+H5TpeI717X-VH5}C(-c|;RPAbYxlwZ7!E9F{MSSLG{ zCAs@Pr}DZUiLTEP+W^M<`j{8BXczUkO(F+AvZq)DJq|ltU{ft>d&oE%IxxZ@rVD## z6uR~!BB-6#Q3Y9y%7~un#1hq(X-p~Ama&$NMCHi%+Yk#TWs56OE6O7F>)%U0Wc;jo zH1v}ZYFiD5BzVj&M!ZE-=Zm(Hb=yUWTA$w!`?NU_z{LrFZi!D z`g{0bwF=UN%?S--UDZd;O#T+-F54P;Gq1_sqLkRyRj==7@aBM0)^Wj)y~#6d)BMdR zl+0Bp6f2WnSf>~h>Xf(y%?OJfW;>Nz7ieDxeBC{;FZigYP%qr zqoJP-Ek~a{1<8>exNj>zEGwY$y4(Tj7k-O~P2S_k#p-oLDW@f|L$GnMqasymyzp@9`6n5^>*2x zhX|#xF}D=ELJCP3YaN22^+Uld2MZ`~48O6tiz zSTasgEu5)m_C0Oq&X9df0oipWfT+^~W*4<-(7oo=GtHIIeV{*5VEdxG@!B^5mV=2T zlXWqXy)7N^m;dX1GWrp{r(e^EIhKKn?ubO; zDmEhDc9cPF2L=z|^bH-C;4B|F@Sp*D{zs|AG)3eF4?Ildt`QE=A4Zl8?tkDwP*3)) z(ii9pyH-7o7)-j;LWA9DX6%onv5Hw@RU7pWAvWe1)k?=gy0GA-HZfjaj%fLzZeITT z(Bg>S@X_H8M~4pk0OjX~ILr|K9QFOpLrni*H)H%fz{{^6qq`sk2{9Y;M8%%2f?q|| z$0pWQTD&Pzg4Zb3+Eu4^yWhFQ7I5BA+(m7vVgq&xG!1%mnv+}%?D4sz3nOP;DGUV? zVNHx$QCCOBC&P1dPiw_CfcsPCq53-D5SlGc5HSPfimt>h1zrAFyxd(Np( zrFulDYQ3N0tP6{@JWZDscgEsemEvAwT6Z=)GD_Pt zXy{fk5BIL{ap3!-K)U!btUAQ8*G_eMk2q0ePtn*c`N_9}BsRY{mW%CWG=qNq4SW~% zV^fX!sdg4L`3RvD`GFx1`wWTs1^ZLtr(Gnc2a?7kVY+vq+qY?|4J~~%j%Yn*wv+FT z<^O26_ztA~2&1FR(K>(A{#gn}O+(Xxw63%wH>``cYPX0JKg#H8WG_R%imr{34LzGD zHDVtgEcD|yi>lycmd>u73)wR^&|jiLTWdk2zmX*_R)l%)D11IR@F=CC`mqbJ@kC(| z0K=OK_M>g6sHIYpzKu#kJkIb@iARQFt#$So*dzqC70*f)k~Q4TSnjE1dM-%VWsIn< z6Nsf|&oT2(z-mov5v&gQ2pn$27aWB})UB10S_QgL^oD=vQ&O*W<0jexXz; z)?Fs;v&Z=1mqLkLFO9~nw-5WVAK_?KF(>7EaRQE;ZMD1UNg&{G#jz46E%my*^gD1+ zc4B*qRN`jbEJlUCr)|0bZu2}k~{|=ET)K|nwTF1V2&P|NpeY5@F z-cZa?3}s}$(2f&d@GT=V*Xq+9!OrVLI5#H^drj*(xo4c)x5&!uCGuKD71>P$A3V4) ze1eFpymg37KdpSScpB{1ME(KJnyG4QQEb)*ji!@<>`P=pxv|%%&T3bSGo`+O8a8^R z#ew~rI+5i5pt~tjb}oEsAB^W!j(T6KJYv^iO@fVa{FTb=$~CE!EA>@AZ=deJF|9x} zi4vl6f}Sz&ThtKg5yya>J~@c$jKwmgZQ))TOPvj>@7M4l1Z|57`iEi(JqgY@J8 zRm6kzEOsr^CJDCA24rjtHf(`Jir>0vTk%?L@d4sk592hz&UW7Y!#C!9T_+Od69j zg_Ey3ilXQJP;-jpi2?Ug=OBh3BFC35eD0GIQ(E;+#De9#pP*r(DH zH{jivPjYDlEGMR72W&z$$sYFWQ>%(uCv!6=>RamV8XroQ14FMc@$1{@-4Oa7 z4~f#+a_SPf1N_kc?y5RyZk}ayT}W}%f>Nz*FCkj+tyLy57+?y7!i=1YxPyGW-B7bl ze%iz2mkfAHK4>Q9?L8$jE0oB*a5hjP3&Q{6UoV^v933Q^kDWRed{j3RZEe)$;Qyz( zOn=sZN6Nr%!jb`_^j6?lFbDDJwEmUgO{~w-d*SDQ#=e(7wNrSfia)WJ$lHWhQEry5 zD^kuT-&2RSs~hobolc8qWV4|ikV^lonN;t_TPgC^v;O*9QXOsABR!6{RXVmk3ot~V zk?JjhmxK49=iAO43szt>UaO6j&vVOQ<2qA&M%?eZQ{fL$3<>S~L<;X>F}eL_XpCXR z2-`+A;tT&c7Q9!tdEnvKV?{tyqBCiOniyTS`e3%KiOFi$nOZNiT7vT$UQp=%z8IFt zvHJ`%tF!wJk+bcvLcr5tj7^f`bWUK4=#txc3uifOk2`CS1>GO}IJMxv30l1oHi13G z%={t$94DDhOY*+!6tkz8)-Pb>HkQL%rrY2$v}cHa=+nf;_Gwg;F;gpBZxRXYddIiS zaegSWd)vM!muJSFK;(CBY)9ZIYGZuHn?GnqJ80!X;6(E|#n8mmuXZu}485E#)t@A) zU*Ze3PG)b47qpXN&Cd3v1$kX=cm2Zbv&T^b#Q@vQG&C&CJgW^d8m8fVnr?VoKgs3l z|J4}H zr~W-aW_%Jb$a)K`|HSZx;EU*kE|BHG(;d zL`%`~KN9KQ?d4}FMEgXpKJL&;XVN@X{h_{Cj@kE!z21IH`(LpGLbZ>6o!4%)oVx3$ z=}#}@cbTQkv)taWgWJR0{3I+;I*~%A@ja5R^3Osm42A3krs4R)SpN&k6yuzn)Gifr z>9DTpK}Go%vy>8<<2#CPL_DVvmfT~(@O+j3P&)md2M^eT8d?MS7V5j*`Z5tVA$gEU zM>vc+^+qv2dulr!Zwq1$pP^TLLvFB0x1M9?z^@cbYuZ!%UkfdgTo+ZUSd zK|CfMC%(IY!i1>FS)CsSiFT$bI_g%_@nDQ@`X|vli=+)&8Nf7WPjSx|%s$GQmM(m{ zJ?>?zX{j?d$i!}IPgIi9DX-X5{FlfWF@9#wy8+rhi?2EYxh8*r$v+f~)qc?I3!D*| z854qrSj?(<&nN~f9i@r>CK3B!g5e^x8iBibVd&JG_CNM%I7GggQ^gY)i6X?@PIOLn zf|`Z57c%}^oxk~lLYWH6M&D-*_?RDD!TesM69$YGEap+A?&to)gU0o%{B%ar**J8O zWk?qI#mWazW3H^%s?XZ&F5Iu`Tfk%tZy!m+4Cj3rt&6c!1r`wxU=?C5cC4ehL;L## z0hU#TmibuWJ%|wYg?jsWd%>c90jOIB--1()k+?{2~hv7S5I z9FsG*D<-!HejJ>9GW{m}Cf{^Z7Oh_!nf@_nZ3p?&h!f$Cx=DJl6zO!g=LIc!geUT5?&h<>i+Z^pJZ>Bs;p(U}I}=-~^jz z&n*>KieyhI@aj=W&>DBAxL72+_KLA)?6_B$4|#c`vPIl3ei4{>4R*l2*7%hgJ^jmC z+Ecze3b&}e$9Wy<%l=02YkG!VIP&{?Ga<9553Y@K5KqrdkDOTGSbm5IJHW^FxDwBM zFV;N6k(&_z_>7_`lPoqZZIU11bWAldnRHs;}xf;=3aHb|am-5*! z1FQ(!T+7q;B$4qOQuS@=)vzDtUG*!_Wq4>Zlf=2$$(yXux?-SPQJtkZqS>esks&Db z8GUEyNvfRJN-c#|uvz?SoS%B>?3DnG#4l5<;C}glDDNySNi8z}rI5TcXP>*KA2T&IBd` z*Nnpa&!xaLk;cIB*mpc0Y71Y33VSQK%6{0>1f{3aT)6|M2RBykRvh{?=w9z!Qp0w0 zXX;kPVT2V&o&X5Bv(#sT(gAwq;oCSDFo@j&suNNxCq1c)WU;g#)~YtD7wYj{ za1yCoLS5J&F+R#*XIa>40H^2+u$2Ygs4mC?_u-OVO%gJqs z%Yfxq{@{4{a#4%!HeSrBPL#)VG5)uqbrQK0R!Xir*2S7rtN5PWYFH&ACwLaMHEM?O zz7_AUcEh4;{wm;wZhmw!$<((9i`=kOd;mX4C!puMRq#VGg-Ni2R6zO(`iBE=pxhCZ z7jW86AiO_l zy;FVkoLbeqefE?yIz;<&K~jO;wT1ia2`72^GliF%0m-&7FTa7j2O23a_eX5LdK)h{ z;p8Ov%n2*-NQsC%jw>S;eM_>4-I;omm;N(1+v$HHk6rHARasrw+9+9CStBoR7%H$d zqF=N>O@N7Yb-B-CSMeycJo=34Pv;eV-7`&O+OgX;I9Xa~+=kP(_+KB9czLNpSLG&A z=l!cfst!|c!;ODcgvEQsDOC(=pFK3gOZ~$n7bCZY80o%0)eaTpz$>r`^EhKd)nJ;Z z&%M~i8~~g$Y5(}gM7V(D`Uw%1;d(utzjptNyP+4miBN}h9%<$(B7||J<$i;FBg(O8 zrx4?Y-Dz9+1{#md*WcY!KJX~~#0g>5)Q&5mT3W^wDHE)frt(?j%9pk0FX9Vrd_pqe zO||e@r-bR(EO$P@n;t8SqW*Z~IpO8!6`WLHZM0AA z;v3*=p?nnQukrQ3sf}q!t4?c$PkCQjbyC%WD~TLy(i|i+UWH5<4xJbm;jd-paPpP# zNz6rFhPH0C$v>>+XP*uf0H)pJwC9i3PJ~a%CO=%8n}W9V+wJ5^RV^&Zo5_`RwdWP1 z_fGL;d$Rw1e6cgqi&eFmt@el?X)4ZGo`(3*Y0g*d6a5r70=FbU@%r&4dh%YyIL3Al z$?CXLT&vo{?Pd3Y(`cE3zXc%QK!V13l&~vva!VK*XzmWXO;!WCt_a3fM%v1)CDU#Y zXZ4VoH~Sw*zsaY0F0*Wj^j7O`QHve6oXo_p6yC(DtMS#zKXcR#6mfL}oTE-Qa!e6U zBgS1pL5^Ne`O^lmD2F&+cxfJC*BtC(ju0^K&SU57|HJ!pI%e{3aZlHctD3 zt^8lm^Ox=oYj&In(0N4X!+xwAlaNnEqP*egBqThi^Ow#K%^~QL+9~21BU>L1eG02Y z$CdXz(8IKB!*S?obQPEVng%xV{vzJPm*Qa?3}|Uy_)bx?gIcLR8`A~;y{5KEO^yGt zrW28x>QU1^jZJ>mBjl1Rzx2>r*L+iJ>lp2qjobVMrOB7^#iKq>X2aJh_NB;s54S$@ zejncd)TenV8F;=rt`d2ZdWRZx{oGi#Na=eQEe)Uh@-Nn)wx6N&vhH`Ar_Nm5MQeWy z_by-gfUk;^-yN^RIc_JB>lmNzYFIemKi##*evALSvb%|vSlFx8-U&z#jYrGBI=+12 z{DEg*15GDUnvPQRim`K_N9XKqW3qQc`UF3vdCfuA6n$SdM&bC=SX8Q`GcAov%Z&l2 zMFfld3wlNjPU?HYe!+JVGG$`nKWm-|8#!P9+UM8L3MT(|b>AM>#Fh4cW+n*%qD1h5 zfS3@_AR80`ijLqD z95aKNwXj|Xg&ycL&0rUNGXlC|=89M3o6$4#jq%b5JMWtYnU=cEY&XDiIoI0b_d~mU zHEfXF=nt=;zx){?Lw~{QI>P`d&{rYMi?BCW=4srIYl^|V&oW|K`xaB4yw89f1!avS zsY7J3!5%O5_`iT{7U&bsfE3dLocSX5j}fF%i#+HZ^gg~gENkR_j~t@=$;FPQa4l*Y z2qi0Vng;dx5nTJ+{qfVNO}_84>=%6BVBX0GPnO5EkQ~<*JF{HOK#d~<{BH17Mbnjo ztH>6T-`?Xl^(-N&1bD3>@N~7Hq8+I9Hd8AP! zDbH1U#?4J;nO8krj*sS{M+3?;&@Q;9TB#Mc+w@IwZXjN)+-{3S$RSMg1pEWRF;2;*d(<{$WvVjs{sYw^-vrb>z+Zuqw2a{s!h&XJKt=rMzVi8{WGrDD$% z&F$U;ypmlqG#_AtplimHDwK93OZitk!B*LBIJP9pH5=TQu-**a;f%AzZROy{$fNX! zWQ!rPF}CqJaQ!K6z>*;@mNFZ%mVHy{z4t-~GrTvVl=OtYF|u*J&FF5GbM)XCFN|$G z)HO!`9JOl78%WbCYYnki+SjSwQD)dX_^jY(^)YZcYRt+nd;6HXJh9*`#J5BlAom}+ z*K-Jz&;9O6Qh%RSbsu5m)i_C)2lizoi6#3oDwh#^7vf6%d%3ffa^I-sf36?zCWJS; zm)fndIjS>(ZI<~4-nSHdJ4k#%afVxT3iMLLXX~!ac^ltKHCy>M9bQUzYyJ~(f3_-* zzMtw&d^ukpSx2io2WqWoIV(_Yjcpy3EMvT96zuPyr>7YQWJe3t@u`2c+{suQYOH9^ zSZ0RQ4ZSEiqLr-cD4*v8g!koJPjS1IxQt~&>jFqUc22$EZCeuUqO%P2K*X2toJ!A) za(qW+#vXOKZxBX{zo{?u52OeN&7ON<-B#-|tzEP>-xn`r!$zxgMX`%}y&dD5@8Liv z@~7zh{=nO|A3cQELHIFMQeQ}(7nZ9!la$(dx+0Q)(Z(`oK_V&f%mj}i3s`23Cm~za zX^1S4O?FjBl~5#RmjIKotF-n&*D#DR4)itpiD_?bY~wD>3q>Mit&zMhH9&psuU+3i zZF;6ijBQLrY;sHXT2LRtkbK_PKX9gUyQ|O_uMXQ1y%6dH95+?Qhmcmn;vpitMBP4i zt=gwje*=#W7d+H%fv#NQ7*u7KgLmp4Vjo)q8;J`fLub%kS7EPM5hZ?DM4aF>TsPv*Zx|MSHq>FYLzNbvEpysyz`;0IfX(n`; zmH`8}cRpa5t!;~H>(K^O&+k3Q!JFnHF>^#+Rwz4QfCWy1W^GH{k8w`3TH;dh{>(o2 zC-|PL)MVq(j&+FYQYAT+{qFdDM_}P#I+4At#_e zqE6hF{dA|i>zo%ghwj|J_Qr?~jdp6Grq_lo2i#k#VTVNg^%KBd>XWYaBt)pcCOT@u z^>f~+^e#`FFEvJR_fhoiEZ3uqJ}(fA4K9)T?FOG!ySw7k%g%Uk!ia<8$q`NMx8@gx z{Gz_LDOwvT*Hy{-w#d%V_#ct;6(wiR6J`8|*CvMZ?}rrET3v}|_P zcZM=2-!dXFCsSQ7%X_>e6Q@zSWrJFbUaJ!`T+!vUQ;9B7o4&A<&JFr5!*_`2@&7{( zUyo!x{&T(O195&vW+}PowF#PjVviqMqTnFW*Ufa@BUpWzak;s+RJ81RdeY+2m?LVadh&S|<_QuDv(%$$j zhzDLs@2JE|gpsfB91Q;I+s=2cKD{ow^_{Dm*Ntj>_3Gv|>QN)W1J(GJZB0*q;iY%3 z+SX;bt(PLRe{ai27=bW><|ODG{A)i*dFIU1;a(bb>dezA&m>}{*q!jXf-MSNI#|%9 zJkyR82fD^sSYvF0kNVSX^4VKk+WUosQ>C?gvG%rl_tx5R5Ay<^{O&(I_wy*xwAR-y z!gKU~ZsHN|qT0HfPsb))q33U-!#NgK3lW|(Pn(`Z3oVIr^+QhvwJ@2>RGlcTHHa9| zz;(E+SW3Qt9h~iwennVcsN)FBG_@V*>W_W&(AGa}s8M=P{f25UGgo;C0ps_!X!kq7 zzgTzW@wXp!WdJL#LONsbfJOK!?^sto(CW?rt*&i4_Jx~La( zz82+dB+d?nFl&S3Mm>x3?QfxeqgLkffzT!4e2F3AmuP_8Y;w@`10njd%t$kj(LrlU zhO_{b~nSkM4SWy_c6HHl{55Y~h@WtyAlj z6^1YzciHNz*{Rp6xv_uo%7j0k_wmzgcmsN<3RK{o*sq5vKqWWSZT|iPvc(DMoxHCw z0W>7{I;cq8r*D50mI@iI`wD+_pLv=ax2Phqv8B;HFQbtgduAi``EX7rz0|u{M!TC! z!CmaSsf;JxgHZO6U)OV|Yc%wC`r}I^VJ{x?n}Cc@E4rz?EyDecU{<>m%zyT zVf(#N!(3ilZB_4hNp-KUwbe#8RxKeKZ9{ELs}R_5xvDh3c0=!I5Ee7jho$+8g=Gtt zRJh`&BL32b(har!8bSFQ<|G_F7c(XwX@3G@>xLy&wd< zz{PJ2Ub(Ca#+ecutFR&*J=ZT=SUlJj#%VfqB#glnx)8>7B}+2!%*Yl4Hp4pX8PH>( z?-RY=4K$5u(uXx)IHBvuxc*$(^*mZ5{r3|PfThm`oI`@dm=c?bB99NldaBtkz@ zXdKb*`q*iP?qf8(7#M&?o(;XYk)lQEUk2#7IHj$~HO@uz=iK*@qtPjW@A@9?U2fky z-SQ6m0U&Gax?Z#&2p*P~Q~2TB#A=-7Nzqb*!;tdQiu)ZbWtXGXk+9pbhUI-UyF^srRHX#Bp(j}9E1;bM z{<6>xc_Uh+40t(Jz~L+LK(j0os2+AUYKD8I#EjXS^ird&t&1-}e=@w$Aw;47Ws{U` zcjIf ze`ZK6e&#*;p?`TxcHMq$T^1o10a^bRQ)yMDPZ zQBAlb87`Bknf|HKig{vYPnaGG(?6iY)IWK%RubM>wWKY-{a0{7k1eiqS&YuTrCC^y zdUMxdM?xiA6bjE3xkm^^h`!7dma9Ozr?_K1KG?V31&tp%!s|}s5 zU%3ihCh!amBCY21MPQHE!3@>0T&b`znx9B`7nZiM@Utg>4On{KnP8&7Tw?}RpDC&Y{g5JOK2gP!MCrFd7)H+ysmn$RhmC zPh`Dw%nDGdhFI(-nfZ6_FR{k;5qrP>ZPsJt1;p;_{)3d8h0CVVN45@4=oKbtu!Yy& z2U{FR@?6$sKhJ`kJLI3&LMVV$(n8=*MP|b)+}GiZJw@~joxkREfv#b`kDXz3s!Ro& z>OR7zQa|3l{K{-QS0JSOPYCH(6}vuO(=Yxbd8>h?J<<-3g}$@SdGeD};_US`+nx1m zx39PaPjSrG>I5E;1vW0A4bX3(b(@Qo=u2Q-G2fq^^->(x__t1yO z{iTh@z^;hcuW#+Q8-RYxOa}24c?0_7;p^1@H^N2~7)fc+w1)-g28@Pk%dcJZG^}SZ zVtyVkrAV(v9jh!rAxdddlU@L$lKji3i3v1@tJrUgA{#LN@fxFF&EMnaaZ@EV^v zi&)GdmdwU!iI@IE9xsCy4Cg_#;LBK7-eA!3f$;3p<}~|KCDnFGLgy^)jqXpr2?BQHgH?N6RTc zt_OxCkf?SrL0SOHh47(nobACGQBMni3PW_aPTWZ2^EN#kJUh%+Q9=6uD#T3J8Y`;b ztfoE=-%HTB$NUUBEc|}ji&RT}L^g7cn`XKH4vjH%`xgTTYKML_C`z+p-9);@I|x5Y zpYD>d#%)Kg9|03<7T;~qPeJEj|@hM$!u+*U~bK7vdiB@B{ef}JD*qM2f`&C)npefPa0ZsRjLyGSyJZ}F9tMCO4c!W`Qq$O;ycaS!B zzoum1^i|O4N6T%&Yz%%N@$!ftNVAy*t#MZu&5h7sxy+5Bxsm2r?H#`;Z1rSdwn_qx zVixPBvQ&kVeHL_r>KX6ZeNY7d~ zY#6u6!dCG-H*9NVze?-*$WbTcy4n4Fc2!K^nVxl?xzKBT=89&b8q$_8o!>&2NBAOt zLfMSwPCjOsySY<{8Hs-mJKy)5BP9jv47f!mXxgh1x7wg_o7m;yYhvN8roje2i;ynv zYq5wKD}HoVLVulV!_1Mb%v7;n1MRGjI5YA%0QtR_?9!^zaW%fn?`7$v&Gca4nNBN4 zYA)yoC+=)?W=K1Mo0kB|>sMYb{c#VjEL=vV=Y;&JWltdw?Y}*RD?DuEa`2=={!gwW zUQcI(u*Z7GyFR^Cd4gp;_)kyVjVI=!_ar$WR~&hlXHKPIf-qtxRxa?u_{_;Kr%&xo zpYNG3KbaL_$bg*ipsX_Na_*EhhFvRayvFpgo`_M|l+LiDFw2t<{ryknCk?x5_Q{(K zyVuspwU!fvESJ&jW`>!eg8DY(r`a>Eoy&6TI%956cQZQe~P2Suegp)T}GhXMZW{w`#V3 zc}{!i%X3k?yZr;N14kI6KRQC=%CYB)F$$HEe`&QD)*)#&jI*&_eLD4h(ZhjIu+H(` zk1;^E%)I-fb6I!4g>$;5@b^CoY}OT9e)9BMoV_AHY0+Z7tf|u*t5M@wR|c-CmW4W1 zhc>G8Nz4$qTHhdvrKPrO?WJd`RaeVa)i2T)e{?QBC#HC_tlA1IB+Eomkp}xV!2(nQ zN2j$X0tns)>`1!(joq($XN&W2wkZ%H)}gO|4c<;SjvsJXnl?6Ul%l8WjlY%GVXcus zH$N1Vpp$VHNJjLGy7Ltl@Gk%tvD;tUP2PFvc^PYr%1nG4=7V%FDVg=3N&BI0VD#-x z`YtJ1tg`iQvogWNTS^^A8x0OkyI@ioiXD+Atz(PhQ-^#+JM*kpJM#<<@K=D76X)P$ zc)iW0FE)T(^iF$=X+OeY#ZicZ6*;EfkC20Zhgdgn9_p43N0`*9(T*98Ipsww7Wvlk zn;k;R=MHO1)QYH-%`0^6H{y?#*R0s=;Ctg(%Jdb4hIu1)TluGs@YD1p#d0a%dKon5 zXbmJ(e3H>V9Wb zx?TGsN6Lzl6{eNda%6i2G+PE7o#oT$&a7mny48Pwv|3KUb%d^cO|_itG_5LGwRhF` ztBk8lS9^hX^75m@*DP8y{IQb9mg7mo(U^j2*~q+)EibQ@P0m@qDDA_(brIEanx$GE z=B$=e9M<90^6>U*In_}uo9)Z+)CfyoJe7g6j6{lbd$pX2)T3}@;jkR7mPfOT$S)fy z#vnEaPmV>*9r|i{9Ab0XzH&SE#ntk791{%H@)V68D6+r+GpzWqhkh?46M zl}^wovxB0X#vIMu{7Qs4)P`9?{xX+9D18MhLuVu?z0r=?_`kA4(!xJi<$0p`$K`V z=qvIp@*h|u4ibmJLX7$T-n}0GhrtcLvyF6~?-E~>dCS3;C`fQWgPz3}Xc0n}AARWs zc;^yYi;()_b#r?w^kSoc=ywup5uyIgZ&_$th_5*7{1#vvsbaTF2JU$C2k>K|>iB|E z8RpIx3LdoM%(4JyzrT4_B%ZcI>jYyNwRrY8w6M4w{TS`Y)6h=kqNp_RQd)TFRCFiL zQ90(K9EaN|pIPTWSItHL`4DfRYdR0VfzHBjptIBVdg7Rw=xe~5*SEA=Bg(F-$^#uA z#v~sDKInCI@_;rr(j=~cN5L~g7TE}^5W2Gh4~)dSWD}d;GS9|3RQ)aRjLLk=uA8A9 z2bq;RfO$Zx_IrJpqsTIL3cQhEwt-ebf8^Jv?M>w!k*(kBE1-82fzqZh%BNn+ZYGQQ$s>z5|@D*)knlj+H6=ZC5;ge+k_7Wiq|}Pe07@V?uG3R^I5Lb%$MEu19sQY zpXv3O2Fv>HpFO4#rf9?r>MitK#&zP_mtsFq?<5Kw{!9;k4cQ0b3IJOfd!7SbJS^i> zo_gTM!TQIUt7yErAaC9ayR0&2z4I!~$#^EBsG&=R)tPMMs+?gPxqReYsc?C=#NaQlGRoc-lFH7pI`r`0^R zm3!&*IbmKdTImj1sB{8Z|2Q-Q4}^+nWmIW)(oSY=7km#Y9K^}43JJDy`I3Dq&7o=E zd+U|!Iy*2R{Vzh->Wq8r%``04Vn2N|g&$vEuOgp?162Rxz!77*N+ z!IfF*(2B;)BZD)i785G7Mrhr`r}wuEpT>OtPzB^_dF~8*TCrJ5l7z~vjL9B0Y@9fw zIYnF!I%`A;ytJr3KF6<#M}Jdw4&w63qUkHNY!)GN#CW1yStAC)8uk5eg?k$yui%H@a&01neEH}O_TVmT+N%(H#V86G0V)+-Yz$QZP5JvRzw3Tmnl_Phe zCRL)Ym7Yq2eRw7`B{HMjX{0Fuyw62aTmj3F+e+JT=CUPWMd95%-GgUii4}RweVT{64fGc!z}I-uJ+uCiNSTd?!*XpSanY?yeiHNtzRSs{ngV z{Q*I$1}0_1Hw#^+@?zI+X`;egk5^hV%w4D1wCk4druwJv_P5)7x7|121Zm*`mGnx4 z_M0kcfh!SjX!~E^z-_zFCA^LuBI)Ja>>H<*cTk@SC^Pi=n{|SBP&+h)6rYxgPv7Jk z_$e4F-q(hCQ1Pn^RIk(A>!kg>uUnmrJa_MuXgANPS=IzMGflLQYbOMouX^<8wL0}> zFFy)CQ?_QGE;0oD!(j>Dus^cX3|Tehr^ae+5QBap^sVy+uGC*6bLW z^F6-5R=pqp(dq{8WU)h80cp1~1X?#CzXxABwoQ10dy%l444^I|+h9kP+PaCX*=@jN z{_vcttaUxG>J)#PKE;bFEZgy%8eWZw|4wLve?n~7&*W^(;jb#KQojjn6rOB`^>^+O zHD(^dX8?VIXQS|J$X|r_z1*@y+K!alk@6KK7m@{kid?Gjy@HTS>fj^x%%(O?G%Rr@Va>1X8HOKYACYw*sf3Th~C!uHO zQ$s(RXbO(`ky0hjc3Hvq354qK?}y}zN)+@byhmxDhVD4utKkjljiS%M1GROh#9Ri8 zV`_W^OO1gq?L^Fh`@52%=@fN3;R)f1UC@Y#n%3nv200TmkZ&gqd^>je2M2kR!6l^Z zU6UehUvt@8zot|1*G0aufp>{q7BmZzkiwxlH zi<`j@6NaZiCX@(!^kTd3NUYT8+76WC0Z+VDD4)Dr!i;tlex%YSH*@TfJ z5KCc4kzt=}|NR=-I~QK7fUkmgQ$51uA136_$>fTc8UjwAH4@kwpztXj2fW`K zX-GGce8xIlUH++Zo$Jjl;CsM+Gs69bR0Vr`0i10ei)c5C`4uL6RYj@&!wR&AJr|T6 z2ao5JUvASt_!kD>>Nc|46E66%MNbiG1X%JUHVRJlX=X4iz9EAFCwZ|N6qu>H%OBBw zpvwTRn$K;uUBvetz&e!t=^GQ@@{5o#B;clg7V>|L8AAgtzo36+NSQI9m*=SR}=skb!otc89F@AGqQv9cxN0IK{ zZM0g1nyJ@9D@j_W?$vBr?%Rx>i?=E*5H3a3De}8M(Uq`t1EC+J#ES`wyZrrny`(Y2 z-<7hQL0LxjmWAp}o_~W_8GbHH7$-&cUz1Uq+i;3AY7$hDUuVFZaNlpjTvyqD5wa9W z-bY?O%}t`YU}q?`@w|7W^P(3#!ep#eZ9~%sosj)NA~UHV>nn#%4V(Qmw9esM%)o7z z{qKW|BKtqbNDQNa->d4P@~Q|EJfcZ*X{R$|L-5jNJ{ZT?c1ZMB&Clny5>@_#9M%Jc zj}Ti7L;stR2EJ>^Z|~`Y_K3#Zvm9RRK)o2lUhR2!R_pR-cX38|j%UmlFAKPXxQS=r zd5OLg^?x<`bgrxF2?0oW>^yVKD z;-+2j>cuG0=dF>1g78`2>FH?A)PTO7MoMh^bJFv+`VLNbr9)7?+@a#01E*OH5A^Wp z9eB$gmY^zlF6+rBodfNj0xzfA;X#vSY`1GprNP^b3Do0m&|vJe;|P^1x5uRT(p#_i z(#w}b`%y?NI?yL659pAB&r0>4=(b5i;s0XXiQD(VZ{@}K_SYIA!*d4VC7yg7QD4ZF z^_|f%DpBJh$pz6~iVkSiQ_vHnk{|0L{WNapc(J}i%Wt)9ZaJF33|8GXt9QA6@Tf6)Z zcTsypDVn~52G*kJ`%^H+Xq^4@EckAp@0v)6G*h78OuQUzlXiNHL0hbymH>`D5K#P& z_W++fCB~3oC(A3pU-NEgP6X@U&f5Dt$FzEcH+0gOk3YB%b`r!ZA*`Sn(b!C=K=Q1h z|B1t~%|ZXrV0=5@IYe&6j`LLp1)8+)W8zpG$w1b%vcb8YfdvMoGsKvJ0Z@ zCZNXvbI7*Hj`v}fVb=Kk&v8bj+ZF&CPBgHK`0?U=(eM8%I7|Z0s5?V^P>kw`RJVd| zf6m?y)=)ab=l0}+7Ym2kGfuwVAqX!IuD=UdGLTDAjzYdwtgr|DO9D@Msf^W-v2Jj` zSa|B#{*FjN@17~X4y)En@ugC}kL9P>OQ|dt0q1d47RzC8F}#YvPc`mj=U3Pldmj`R zd8vd`0wl=_`ri-GXq<9o;oIXem-zj^3X(U{Tu55y01aZwl^Jidw8y|dpq-{w(jFmv z9HF^LLB3i#ewD zJs>m*y?Y(_dX{+wiH3GIx&!NA+quHUiQGQs%aOe z3tv}#z`axL6Skqx%PFu)RP77G9!CQ-I6WxvpkEKfe>>&43pPc*!LqQ6>|uibW7l)+ zI_$j2Rw3Z6lK66rQs^k(yHH@*2)ym@G4W)|L?6|cOPgPt1m ziLyF57I{7&V5x*tv~2%47e|OEBM&J#k~MI)J*Axu|2wpdL%Fb|3SO1fL2cLa^O2F< zZsCn|F}{-dX3O(k1%<*1VYlA%Vqst8_(*{EdsL6itmB@=Ha6;*hxi#Zld6L19Bwz& z{N&8BTZE!{>B*tCHh0E-DtI7rar1bKV@-q5U12z)`2N%*m&-Mz6Oew$%Xx zhBNRk^3af)9(RhaBQq|aw42qZ??H+vq_|i3$!o>+9k}LkJx(|anL|8$i_y+sEscUM zpao?DI;dIp3`2>4O13rVpWe+`0{*{XN2-Sh_n?0Q_E%&h#7&2-BJc-)z*L8^H_-o$Fy?h+4n|!5*pB{6Ncp!v#7Y_@W zTj!jR|8;0hf=|*xb57p_k2OX77xy|mRaLOx_5gVtyN)(^p1@dy)#XikJo+Zrf+zro z!igbS2-!(DyY$UkNG7!HOv(jnTRcaU%@(;%GAo`-E`WP_xfK>s3az$IK8I3~M`G5} z2>xOfsIk%RnDjA9OKGErjLsP~dbED%=p2OU{Uk_@4+`*E;Y5FPOa;{l?&VMqFAa9t zt~eL*_RHQBg!uN-MQ<$R(7eyhn|y9ab_C2tKj5DAQq1U(|2NQ@)C#BQ-NH%y-z)sj zzqHGtTiPXzq@_>kLwqb_(7y+q68`lb|5or6qTAHF!O!|FakF~-_racsxLG~^rI1|^ zsus~5>SChv35)h{AWUgkfuG53CY?Styo?0>?*>YeGvdL=1^?SDCOC2lX)5EI_t(uU zn_2pM=x>!XV%=BMzzdcPg-!2 z4(qJ*gNjVLcZ2e^p@FA*w84Sz=bz{DHNn1}FWRuC#A`Z37N>9U`WJ21O9R*QcTOx= zknl?5{-EsB2KCtm=Y;|m?A!BdVdTk4gBkYpPM>=HtA*A}{CYljQi1in#`;P}UlkiR z#PzjR;eY3krWxodzB%+aDia$q+w(;tO7RQ4U*?AG5B78$b$x?L+3<6arw!^ZZ?Q$3 zTpO=LIrw8_!+g$JEq<0z-{=bV`1%I*{ZQTlZIH=zg%Q1F;E&aT!aNBZ*;hKWD(iWj zwZ*#ywPBf)OMSl;kH|k zwo}Tj)Q<(Vz4b%eOOgIzJcCT%L8l z|1XRIUFXpJiBy8Fp@C|YU@(;+FEXeNY%b&jnoA5RwI@sBVbNkKI<~n`Jo$Pjrp$tu zJEFLjo2@tXJU11kkPo8uyz~V}k2-d+a3o4G9A7We3S5_nx*)%4R^cb&G%?}$Aol~V z{T+Szhda24h=8v9l63|UdHhzi({MH{+@_;ocM=WEzjJ?&7q9<4zwqp_gB^U|a_mC6 z+;6>F@tD^xKJ8sEHhUiuAN5**5A#+huNz+w=cPWAin)&Zb_7-reN&`CJ41#n4CA}B z&|tF5{^MN*2JErmi&2xiZ}t>#ef02d||HZj63n++S4F5jKVP>V zrf2E6!QW$gw$N0ZI^CymHwV>xcsZKgBPHqv{OX`B!~MdhgWykb23?vu$Wrc+2K*}T z5=??^2Dj}JhcFo-T_?HolxuCv{b`Gmqs7(9Q3cy=gN{KqxqN=o6U`%2H`tOK+{v9u z4>+s|K5*f_@!pqq&O1NN>%AxKET|49b4$;9<3YEf-B6}fd=IYp=zOIef9xE}nR#e| zsNA?V@?tj8?G%9Gn@5jYuIN1;zjOLGEATwM`Ts?baTNMEvi%oZwBq z->4~~Z!G&?I;h6oZM}DS;5@LF8+j8RXw_wHjecs6HwQ@T%py0zpUp4wuQ-G_`bf}L>JxK!^V`uIYvobMZIklz3J=D%gjZ5b&>qQ{Si zW%vB%d%+z)ah-DP2*ehT#7N6Vo@WD`F|H`+Uv!-}#v=SBR#%o9^bhF4F7UbxtN5B6 zZuke@8uYE%RyN;>cBXM~quvn>5e;=9mtMi~z;Dzalb!ql&>NrN5Wt6}eCw># zLnq-m;sNl<>SA?~4xTqTBkxo3gY7EgHUD1@Q9SVmNS4kOUGsl@2>KnkW+|Le0M7O` ztmZuMArtKI`-c1Rlvi)sw{NC}<{+MZt@m1G4pRbgC#dF@fRGspoC?NtEvc|8WX8GB zmKmI{E*^}wFv6E_uCiByd==%V`oex(M6Uo18}groOyHVda~=CESv5^v93}Br+82?J z%a+Ttp6&7K&_*g2Q0D`kMbCjF06(3r_*Z`;Ourw#+G@t+OZTH4Ox(kT+TvaCMjmy7 zzsh1a*fb~A)1L#fbuEwuh?-VLV2c&)F%O5~Kp)X6^@IG?TmXu4!8L#GAxINabSP7& zqAQ~osRR)-Dxe=22mO!;=)Ya_PYiIAu6jt?0sf}g?X?!q0H2iP*J{W*di;-p3RNjG zoL7Mae@KzrkTz=oG9LHgzCyWE z`XPaJ6zKK6ZAq!LO?{3L3J&x|I}JQn$yq|_gd4cQCVS#VEx6`=AO(<{V$8_tAr-LH zMDdpjhV>GZqsMQA9BG7eb{AGD$hdV3h>D7#8UGCKOtmQ>I&Ma^=^w^<)X(rp!_+r-}@JnsR> zg+m!gf9wNim9!s}!+Xv*1`Ai6ak~^MqR0Ox@P^9TNKz3Saw4VG_lDCT8pe@biN%!W z8yc-MCWy_5ztpq8z$P|`yh(?>3;Z+poG2XQroPZ}dHJ*V$%aXvg70~soP`0 zo2B$uuJ$RGDsT6&%slMBd;HG?!@M{xteD@X)=*!ho&C-9TYJVx_oAe`Y}uZbI7`CW zC{H8K;&GPlxrDR+I7{`6DZdvb-enu=S&1_p&JsM0IMd>6faemQvVnJ`>;QH%_$*cz`yWaeUo|y)z=RjL^CvuFGD+~ z6qLe`q!$D1BnISh1AI-Aq%g1B04$I&4|K?M1H1|Ao90P-Y-#SVm(-)YoXHFcu3$QP zd4nphdD7tl#qLFQ@S6bt2>PL(E6oW~#E3-Ct|j0ixrI)%ir)KGh>-G8-WhhtcpCK1--ZmXpYj#Uib zOIALzW?beYSqLALN>(m@sN~V5t4EcxX^WSZ8RnI&s$kIP>-~`og~K`VjMcYFTn@<*QcWos*U= zUsm!+*`0Xh2b9n0!N79r4TauNgNXNWKLXbjYH{6yFse5`64&%xbni8!LCSTX-f&gf z%F^Y_CQL9C&Y3f7&ICi=(v@W;i`N=(bD2_Q$LsL+P|g8Zz!{Fw&C zm6t3vEM8f@rflWUNqaLBOUjp)EjFxPZYV{rtIG_lrLuo}v}{dzY1srr+Tx!dpZjQO zY1yh(4?Vhc=~~0e-q%t_w|Ttx&FHW5nF@y%hYp7xM}HjgIFfJ}`1x6j%hqJAUcGj1 zB@3bY|LLcEtC=I2c2fq^{&ob@uEnuGooRnVhZ(j3xNgSLg!3DjyoB?OIG)AvT<@`V z4E)RCFlICDLA?hnDyc?Z*8MqF1e)873^*(3DLZ{$4&C-nV` zanSc)hJ(KUlQ>j3p2tD`?^7Ha93zpK`onxArk6D!Q6xg@B-AhLxS;-UG#0c0LT4Id z)F0>teJMnSF%*7>_v#U%_wf`~3rwI88L1E&UXEaDy8c|tG!*LlvIvC4-`3Lgj(#i> zq5TYWPZ2t+lUX#vy0l?Thw$hpnXC`O_J_x^z6e?5WEO+4eAz>6S;;bHUWN{kPA#$R z0jA&=j?NF`8Ft$k+nW5*yPqJmp50^FhLG*uk?;V8KdvbnPNCt!x=VQoS=pCIl(71* zPbr~0cCHelJW9xx{Ai_gtY&{Ww5|(>Y+7&F-@5BX`ZZ7ab^kw3{q9%QQ!?|DI=;Un zVakMB%lFT$ExhyHO($MxJho?2_G|mTFjK=G}%hcg!DE$zsu&czm{vqsKFj<9LBn%0=HAWxA2u@O4a^f#b$?R_}Qk zLOSUFBfVkTs;snCEbErm7&&_M*fAE%%{!>Eh0UEeGkeUG@GpE(G;Tr8<6|GdbfCPK z=zE?;G@yew44V+yaO$VfI_^dR{_l`K+BZDUBPm}8S?~Y-NNzKUc0DD?X**h=8IQS|>U?nav1hFl`H+`RQ>Tx62QeCu_;A$ser*MpM> z&cF5AIFvbVy-qi1YHqzAZPeG@dOd#1z=OA5^F>UL@4{~UqNZugw_e9i2him$@d?EP z=ihprGJ`p8y&f@7Q*-O}n7j3Lw_Z=UXW+qGu9Z1o%UeMK(jqcHj3pZi?ZiG&i#;00 t#@{Fz!uFd({kEsQ=ykHp)FC-P2Pq#Nxo%{{xvY7ta6y literal 0 HcmV?d00001 diff --git a/boards/ark/fmu-v6x/extras/px4_io-v2_default.bin b/boards/ark/fmu-v6x/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000000000000000000000000000000000..51403914013d2f9cecc849dfda750db977a95303 GIT binary patch literal 39924 zcmeFZiGNhp{Xcxpy?2&O1~OTIY``o5k_<~Api!_6Gs(>|!Jx4%0=5@}_9AGasEu7@ zAXrDx7Kyb;T+nD;ur)IfOVBt`v~{WN3`@U2q(rffBwFu4VD4m_=Y3{ErN8gXN9o8x@k5FaJh)Wgnz75}?3aNNX{WeSjJ2+w%CJ-|r#Ju(uqJI>> zqn)H+u6y2f`O<1B%Qm-aZuPvHQb~}EQl>m-nM%$Oui#r+qPrb-3NW=mOe!Jwz0e9*HnOS06`#}|t9X)lC^NY`rE&SjV8{Kg)19ZJ}!dGNaBisyB?Qg0#E7`ayND7N==m{AQ0-{Q|6piT$zfH z(sQ26x-n#T6D3VkuNIhi-A#eH;v*uB2*wv9dMz0w&Tr4B|Jq|~IiK$RR3#;buAcMn z6s662gXo5|s;ytIKV;w)Bk$@@;rBUQ{d)edsP*HaU!PylRVm~hW9^8!`zxhI)TA9d ztyc9A%<+%p2G!W7RgBs{Ip+53bo(7kTu#;KAcH+l{{>IonGmO~15RoKrukX(_42C@ z&Sj8}hZ~hi%1k?|ui+IPe}if>lOpuMX9Y}_ zEDPpG_#vWrmopr&_W!GX39GYPrZ!g3=%FrDd2^$<%u z`pIRrw`{1tGplih{>Yu5$@_+t^D9z#WjaqwKa*DJUHv4})Yu|f20Q9^s%uQNC_e-m zZP=;aLQ)F3puUg`rTAQfp8E90kEQg+ooWL~U1u9~)a&t<)Tge=XavlIj*azzm@Co; zP`BZ9xMf3b<8pbQ`XjTWpK}@{V(sy_<5yFqsnfIJyLok}t4pr(xfC;vM<4nR%(lTD zcUgdqLG+W?m@W65cbJ+gTQ;<)TNC%Z#+$Hum&$tZuB=lK6a7Az#24%LCiLr}5BuZM zm2tC3l`ZNw{s)1E6&{5S}(i1V07N;?IRDHxe z-5y-cM<{0q5ZimI*Nm&g)J@DI;j&I%Y?FN#HgCFlok@Ic!}o%|3%fRHgN}1F^GRoJ zuu;h-7^(4H-OcM78dHt|tDx{1V-<>CV{5#54KaTkw&9&)(1Z6mV>9snT$mJJ6?|M> zQ?l1b?RA5myN!XmL9&t9GF^|W4Q5iD6>wOIH52@#gm017+)0!#hfjoa#eawUeXTOD zlyD`**`Z9d%m`)3fr%Nz#LAx1#qO_64yrUBB&4kK!42B#V)3_lPnFw-1TnjdJrl(|Y!=J9Cru&x zvd%0KaNlcf%#_>wPikLKe^iolY(J>otDSVrEE45noZ9w-64JFg_THSK$sZ8Ya1NAbog)dv7vDl>*%FfLWP_wCfr@FPogi&2S6K2#OH~Y*9n2GXE z04rrF>(q!_H<-n(s$_~s*NpAmkX4h{*y_v=au=GM?Ed_PdvMo;fa&=YtB92-e~VeM zt8Ace8+P##NotHoUmM-i*!@)**6O8h%+MlKoekr@l&|_1WD=<&3BJwvH>0O`^xgQG z#(H0puAT$bjJ`I+7!`RyL1n08tFbj|#8&6kSyXSM`_h<#V{Q^HB4H8}fW#HI{Vo9VOlI=;?X+-z$;|@4qRqR%$qthsxzvHa@DA*Ivw{# zqZ85Y)wnFCq4$+Tq=4EcEc-t6g=*hN%~yB*C|?#!N*`5IK=IQ@OGUbnpZ#q}=xFLr z_PYo2;19SC;Cc_&<@{D(a~P1Dd<>$$jcG6Y^_Q_re3-$;;K~H=nGn&^6hJe7)G(V1 zO)$r!AC2^Z^ZaF`Th*F)lw@OGTn8vJF(;?o3Q3d3w@O@dD@n8NcDS&Hn>N}Mo?i*x zmRZx(No-l-_03+VHb_f#b}nM#qM!_7j_T&@gcQIm}FG|f+@u+MiI^%Sa)C~N_ zbaRA=N$3wXb+dLi=MufvZR+F)NEYT$LKSC>6uuU~ZpQvg_RZcd>niE2kYAGv6e_$X zmCKejOXZq1PWgzmROZ{ZCFW}#j5}8eR;7tsWz2MKmrA;O&T<(`Wv}dj^zvwRM~OW< zV6^E22JpP?Oh)7PMBBx1JbG)uB_EfW1o=*W@UpF+QiF?=&iI**0(eMCXNo(eDhHe+ zSJc<0EPLm?&hn&_3+bRcm2~rxRidTE(uMGjZ%E%RTzhamh3j!#-=5carYS-i7yR~o z%H~JK+eI#7<}hB%oU%S1*1c2}?4M&y&u64BALHtA5fjmqFGydB zK+KO$CHi}DWp;XO>qPph02uLD#H~zLQhzDm7DO;ZTXse}UBT zhco<~hv}0{i*2gZcmDT#eK%1Y>SP-)u{DW?Df*zwq#;wMYnq|_F((O`y3KbYl%G;!VIk?ofF+h&XOA+ai)acU(*7v;DHoMgHE^^lu^?C3Ml!VH5M@v zrVFMQ^ASBC#&6Kc^ljo-;nb`WefRWEVy3UKd6B~X0b=HMX*zCJh2bW~ zwZsNU#=P~rDoJ51*s!5UWW2Y@(RO=w<(#u>UB&i}*tC*4e!55yz2alyUgz-unE?ti zKqpUa-=62+%XWadVY~JAJpUX&r}Ca#Te`nef72BKQ^Ouge`p&hKUp(7)UaWzN;{~f z_ja?mt5S$$5TcwLYuKO_nJnnNeOG1N{}Aevxxtf-3Qtai$;=DTO$_8{c+S~qU5l(0 zkEmIm38FqykWwYmokTf2CQO^wOA0PQMcbZo<{rVw4|=Ry(AROb+dM*Z+2RO$JN;;x`SjJBil4q$Y-!2TM9+ksbQX^VXGI!(l+cK{p3z-LbH z+-7>kWF@Yh7o>CT35b(>ZlF2tU*ENUL!p=_V+E(_PO{!vyX$~O;BYf5YfF@^-@u+q`EQ+G&vySU z_b+y2x*G0s`}$=13a2y<(>7w~KJAl`W%Tn$Y>#I6^H7!@D80W*%n$Ie)~32(IgC#AvE37o z?v68T{AIKZ*ic(&sbCL;h^C!S=G{cN<5t1G!&0MGitCX;mhkAP~ULWDYDXMM}=vo-jqoEsvuepCR);v z!SZd`DJI+h8Z|DS^i|NqzaK~uZr{Fl9JfL+Nu>-r2Ki?rk0*A?$ITkiDB67=%Py?? z$CAdjU1GWvXom;<>@}|y9`=wz+9(JNBl9T38HhUcBbfwRL>%DQoxk-2O zjSJg0{Semdq|9fW>w`_*rFc$3d5m#`%}L7qjvlW**}nZ2$b$@jTP|Ik20iLh9qXfK z9!b)y;nOpZSRYN+`N+?BvmFvG6t+Iv_sITOaY=@s_%m{q@ON#W-`+63Cj6%j+n-1O zec|V~OKi6$YKOzOY~O<##GiPR+r!%aDhb;nh2!;sGmmH@@kRQ8?Lj(6INq?`EVj4A zqj$zH`hSJ-1L35+bDlHZ6^|}{n-p#fG5h@)rvX^lys0I0ug@+wNbBWxX+SVp|jY{laiUd$%-fur#%;V=~hY@0D;Adv^`vHJ^`S zzT+MbwtIWQYtJ<2btQH(o|E#9)%+K@b3D2?ek82I3J}D3;&*HJN53ib-7f)B`VtSh zn6RZ)M?8A$?e8>&uY&E{Ew|sYAi~8?7i17VHpVeYym{86i8-vh)=yvARr$K} ztKgYOK8KDGywUDIvz1W`U6kyLUU3||^ZZgBc;^mrDzIi(g=rbROR?YRtKfI|l>+^M zww-+V&{^SDtCE)R)1KT+loHrI$?;5`x>{;AV-@4k)Zw~|@r?~0Vr%y#SE}~FLh!*d z=v1~*L#;;KALB||oC5q5?Os~i?kVd=OXW{Pr0{w8TW z7HBLjWbn-^o)U^j--+|hZ~D$W%tN#0?ODN@V!KQVQv0kZ=Yo${XpVe-f)ubmt>Tez zgFH*j7e5Yj;wQL>?IX+}mH#W72mfK1;d}%5GQ&Gnlr9cFW(unf+I)b?PuO+^wb!+D zmNwPa)w-8RzmQmz!tHi1OWrLayVtmTtc8guP8p2xw!Qa>?#i0?&kChl+uoK6_f?Pv zht86M*EYYe_5d3{8(Zp@#i?%r?H--hk6Ppz2o1SwB0s(Q*(vJ3K<&4b0ohmoS3UFukoh|XcK28Vl>mnGU>5pHqb%y5KeJAF~Gb4z2=R zOK{Z!m*u#da1|93{oTNMIo_4wcRsG!xUzBGT1xaEUPJVgQ0M)tnEgo#9Or7CYb}DC zJT729yWojR`eHu0ndtYUpW4DE_z8_-*75HoNKRKg`kZPNb+!7ci++c?$Uz3)Cr*h; z4#t-m?;i%7%VwiJ#;q;XcN&kU)ZCz!l&tb`13lag;K5pVu8fQAPOHX!5x!d1hSg_t zW3aRKm)o_auxsHzRJ#(gUgOS}X9L3rW2UY%+iB^U7G~2X+IFU+>?xGJ7V~s{CkdD= zB=(d~iS0~FiaSrP?@G!6=2fMO+x+Okej)U2m;w(Gz;X%40_xg)*>cB_M{%SyRZ`fv z$#K%$Mscd#g!Qf--s9W5orjl-v+IJd$}RG4Cl6n@k?8sgMb~ITS5wm&iB@aEZnb&Gy6WX>?6g^y9cNO?wh_sIGMi2@4z^A$aR~(bQSB594o5 zT7{Jt<99I#w!!b4)La{tZ3GbvFHJy`gf8XNlp2#<;^Q{#cIu(U^J^Kdll6%?942zo zbN+dl(dVV{H5mWeOXDvzi%jEUv;`kv{5$Hhdvk@9qjqneF!5MY8;M6J#}o2?_W4tV zB3%-Xz7Q|)_lIYD{vFnJ%07J!v2+ZdJI@Vg!s`khVB-oG-64Z-e?7t{YqjW)UHgtHZoK?LEDO1?D0A+?qHia#P zHT?GE-u3*x`HA{#)I3-P)vzi}HM~?PrnZqMl5kIelsE2XM7}KXH}1 zXgQg)DD*d#IGFA8D*Ak?{5ALwF8ZI}%s2_x_Ox1NwyoiD7fcOn+P8CvB-@lje5R|t zMTnGhmiyM+$D5gN>KtbB;(bK{Fw09>s9>{dbP2i<4{(j8F<%-x3g&po5#s80jQ27gT;gWF8d8)M z*e324J>qh45_;b`Cgv}CbGFDW)DCQ=%n}`lzeM2qDJ&0?0bNRuN_H$qy$8kw@p`dJ z9E;vHwhumg{k65_!ZlZxzgdwFeXCj(j31~yQqo_;_&S~PeHFTO;o%@vq_N}b!V+4d zEq}&2`7mAhmQx8eDq0c_yH%kMk%8%Ykv>M1+OaJnebNkiqlU5QHDfoH{~dI`k{n^w zPJ-Zxp#<+u@QZ}MlPDekiB7`PXvVl%6TmNzs6FNzRI{nNYxTOealWVzrHgwiiIS(% zl0D9EL)5H>DL55XJ|9B-B*AYr?rgct*YW^w=RzGZBm9Vs3WvXpR|=xOQ*eLb&z1>d zDMVR{=o(^2W2}tvycIr=Yz8krqV9nw~XY|96UWIK`}Lrlp3cg)09uRw#0~ zA4zzK%D`91oAeY_CIFtvq^z68Vc5Kq?IWP;t+FN)QdZ6eoaG zAc0GILlcuF``Ai!FyF>_Ph{pqtTF3nLX}3YP)j8ulYv7#_Epm^PqL@>^_j4eh%zx@ zVM$mGcwQ5H{8HZ~J|0}29z{-q2mBo?&HTnpTATx?)0`ZO7LJZftAw;rJEw?~-C9VD zsd79zHk{^LzhSZT0)wk1DZRM4=|O&O7JPGAq1!iDWP^(o+`hIqF*Bm1tBCA^X4Gzr zeESA#Kjpp+Tjg&++mnQ^$La6N&M9uz``?E*zz;)|(?egl1P6V*06NbRv}G|r`Z7^& zR$cjmXbMu1zD$+B$1LE;M9EMEvBXEGvS%-BD3;H|d~^STX1#xynop0*{FcikJ~6Le zcaP6{|2C&K#7DAdNf-8_GO7xFX0bqqH(Q~xOZI9RWI6xyRZOSZI=-ghboeLd;&Ij)0cg}7dpw|gde5US1hlTZkKmU zUxxFblMtnSA^%+)tk)XX^0njx)d+UJl}@T5Cn17925h;jV#7U{g) z25$wm6*X^%C$~ki%ZD&Nzveqkz&i_x|L1Xk44H{I@DNJ9$yJ|J&1h@mNc#g?yFT=P zVkkWF<00?)L}t=FeUKtzFbQ51<~;zP)1C;oKcKN+3<=O8iE>_zgfG!W_mxD?B$OZ` zW}pWR@U)dgZq#Ai7B9x$ujcRh@lZ=FcaZ!{2tJHANohlO5#_}=lURen=eJ)aItR(! z&$kfeC-I|dc}J)0?$>B;UCZj8?ujx{dYPjuyx$*x26Eu%Se}+0oLU z%1?DX*q@3vL}`fscxc-Yi}5H0V~O@QR>Q&Uf#2F1XA>IjydR z{s#}Phbj}*Vt6lPw45F@MN-oQ5i}M`&``m6e52(zKKcsVvs>fL>q~dF59qla&PM`0 zxx{>x=nXi^i6X~Yn|~#^#pmJphr1Uu8`jj>vRx4KG?R{A-Q|%BeJ)4`E>r;O_6#xn zrY0iDpTSEIkKQoWz8x6{4ec#SUnG2CC{6Cp`~wB>J7gbB@_VAZI!0_(cr&xHlZr>J zBC%;L)J&CvQTASI;qW{SlFHN#JdRU;3)WQ|q8n1-d&%=7-wAqok{2`Sg?i&U{+0(c z#VH}phT?=yU+f`Px|IX2KORo<5$sw5Z&*R0yXZPt*5!q6$;|Gv+<(Sj_B7MY{u0GH zq7kcnBqHf%-&+V>H+vD2$FDo1p&smt%n>G&xmnrQkw}kb*1cv{Vi%fT7_TzD{)$3-D+kJEwquq|IEhUYwEtVevoay{BPNYNcDIdSfKw8vh5!SFZID>j1l(Tt^{vb5Ztzp z6wSLVX5^BYcV?|Rz4}gRqWr#U^w5RVy4c<~jn3{X5n=t=9+OvP(_`uK{H}Iq)~D%m zQCC*=7r9@DO`<_m!d{s#Pd*ii6KgP!QBxn&Tr&C|lb>+54^aMv0bY1+K%kFF--KX$ zfEvFZc}*IR;IdrN%_Q(CXtSv^t=1~9M1C4wOzf?a_R|?6nQ4T*X~RUCEGriXuHB^ z04yg*h*^>@`4h4cuRI%OzMuC-&N1FbB9N5vf3m(o`D~wCnZJ(x=FuxJ9g3K3sS1}>Xwz^L}5j+dC@7^HZQTIkc@eID=>3F^Cf zcfx)c_jxgUfYCw5G99Axb7iXhXm}~87=CZ1dzfjidGHNAGAy{h@YniMYqgPkARy+0 zE;3ZRd{3zj@F|;%Wc*!v&wQfnM0|<$$^30B_hGYBA4F~}vpZ*>-;vz z{PFGU5&H~%k;qv=#v{?z>N{1Jy+*LP*WvZ@<=X5*d<&osSvb|Ps2B!<{(*gTBND&uF?-?Bcl zyx}LdM5gU~>VXny0UO^#cd!)s_td9K6kGdGAR7|v4!^og%2=i$Y%`44)S0?$HZc9! zP?ay`Isq7+FBgGptcx>@mP$?C44+L7hR^;3Nqn+)33<2P>}%iNE6`)$_iFogmf6wX zf{ehk6H6N!AS?Gf?=*^}cy1`WCIgmwc4&$_M^5juiKe%*D{s8by@A7ct+%=5Be!ke zkogmn+r8FfbHmH!*|>eJ>8*HlW+12@FfYAr%WYd4-@PrUzGdcqqO0k_JJ=0BLA|?s z@XqvB(#~XXedr+ilFkhGZ#(kk(dZXrm=V>;jISg4d_2>~EH>Pk&|}8eXEYid(@5=i z(w8$@&)mti+8Q%kiLK!_$V8Q`S6OGv`cI|`3EKF%kFEQ}6NlCpBf>$z!+$l#i=VGA zF8{pYmi0H}-O`W^{z`1apo1pl;}{dzy?dwxG<+oX-#Gr$*#E|H*=0CJG;KYTT3Mpa zM>kQ0r}3yOKD!(lTf&;WLh;XMCw~7fPy-JiOcVC;p?sEYcfC(vZbq(2PcHi_)MS^p zAj77qQWh_SapJ%p4S)OgAO1;2#NY`z-Bf81*)x}TCd2?+or*m8$_n*T4CW+!2Va1X zaBeDsdXz(e@$%o<*k{S#tS?sMp03Nwd&kRF?6b)%#-jXCeKkiDN#oZfbLbGk3g*)C z_s-HxVMY$}ZAqmC84kaf^<_Wx?DCkVFZ1+CR#jNt=KWl5?02~u`|Dk1vEDOi)@0g4`3W>Hh;^N|;XZ1DxFv7A_@ieKdNkr%W?@s0A>Q~4Z;?4c{yJRdO<~@#yZcs25S8SnpW$ZzIcL zDv8p@MZ%-ey`wyMn{dhuf6sJS7Z-Y|`Cs9&=uHVvhTe<)piEYcwiPad{Kw*Q zP5JtDHeZf6-DmcCoton}O2EPb-uDzd6uHPXQNkU_(b65}QxJEtljHDWm#osq!l~H5 zNiXdE*sZU}WoBEBThqtXJ?37&ReE3D<4EM`buU!8C6?)j&QIhE@U#$F{2yieV_5UT z$-N(}Jbad3VJhD!rTU(bpOG@WtUR;4&0m1K)5|g(t;!~3;&YQ6c+t&LhQ9Uz%td+nEV@u zm{@~=wb$PR$P@O@?8*?C=L+f~nVK0m1M<4_8t6rcXvaH&4aZ^D-^RGn#t##zeBHu* zR&Rs+s`H8?&&&1Dlu~`q!*aBG>+@3WrV}sw+x%;C8tSd(RUY$Yknyg159_lu-ryA$ zUZN_7ANF=;yukM=w5{UlIMV|wK<%C(TM{`AqKRa3 zEPDJ{1$Tn!p_!@!5WWJx&r@OIiN~2-j7N*$dCT@OTMW7uFj3a6>^FK-#R)l`G0p_* zu_(Xy*jYLyd)56?VR?%05AvhZRB!&O-}%4Edop`=`BOL4d8T{Hy=^NC2IJsen}mE< zIWVt)zu)^d2b=N{r}4-W{wK3v$b0IB>pasuZ7VOW#(K{{SOIs3htdkZVJRpXjlMq2 zB+TSemJfR7mNN}!)+Vj8f|9XlH>|HSx9+)vAlA&w?YG9GFOEjTu&1O{IkQVIRYCu8 z%h}RUI29TZ-&G~)@rD=mko*~PhOY+EABt7@61kk5#7@+t%AB~}=kc|`H<2qFBvvB@ zkrOw{>^`Q2wK|7Fuon-oeh4f{PDTc3*Gh?v3hpYiw>S8z(DxQ+okF-t0V=zt90|2h zPHZl~#!H!9@0^9is9ceND0r4ESkRR!m3GyjA4I21kwGm*!z*zSf=J2TI}kTXl@K}M zxhj{7m>E1w|8MF<#+9X9=474wUsKKua~06wZE$7RR18pfM*gCfNC{~H8{v}8V5*&S z)>}12w8Bq1QC!(|T3zVDwFB24Tpb@&z&f?rq^m&xFISF5r;M&pg~jz1=Z>tZP!8{^ zgugWK739NeoLyrV%b8{OLZ1bmLV`Rrrgt(O6?vTEd|%Zxu5e+XQTZWBzMEe3EV2yv zAsXT3RM+kR4+#Hv$@c#$0andyeWn*Z9U$@t;Qw^Iw~71tPX1NcZFwx4QiD7~WQPv$ z9Zi)APE|}0w|D47?qybX4Pv21cqWRd3eV6h*uMWQEL+J(VNYoAK3gpk>2CJ4NL?bO zB0G=ezz&65WNuxnQ+N1XIdmhjw8-xwKHegQZfvU5xarlrq;Yd=T#1$A=BG9>o!eeb z^bg{KO^ceK6*uV5&FZjUByj6^Io1aDssdlm4&)*{)bW@~_8f$biQT#7U}Q#`E=VKD z%3O3kY*ZWUiO>2TV_9<%E|ry@3zAs|>-WSiu`65G?wC@EEMr>(I zgRe$P_+EdC{f6T?$mz@oaKpMQxnb=U)ru!Y*LN^7Cv7%rmZbHEsuh|7pZ{Jq{y#zn zP$Q3S0$^B0hgPlc+=R6!ujs zTuL?0_5Dw{TG6K*#a~lODBN{{Z2HrYgOQ)5&B2KGq!r`u?P&#}qCwBP=|d04st3va zZ-);?iqlLX)-R(vE@Dy}F9%kv}=TI!07nR>68j!hVlXHVrlr8c z#sM$u(tZ$H+{NG)f|yUEF+ltdKQL8K3T=vsf190Ct8eo=oF_HhvE}``l+>WXN?HM1 zN;TF2K8ChE11Tv#23}8UK7ky#>ljYv8M-Q_!%uhT$?|h1n&U7P4f*+yO-VPfx4DWb zZGBL?*Ik~ePFPZ6zd2Mq*i%!in8r)>X&Xbi3Qf}n{Z7xhM?C&qZXiW>&VNJRVgH)G z|AyA%@9`JG9yu6Uk=Ew7feIVBkUynp=JAx`g5#&Z;*_FH8~$l*wn+wSkusTY^W)Ul zCNB8Hev~Yl%3U~i2JY#$nxJ7q-skfdA z*MKH>S}IoR-h+=hJovk<%OqL&rUhE4hkv=dMb+n=Y!) z>Gkh(4)*4Xe&=feGV_gGh7)VBWPB9XXL^V(Iw*crQTXXg11Wr0#RpjDspZTsG&4ln zrk1CM>%`L-o%}c}u)@-8vB}&bmihL@e;_y=%vHFwtbpBOwxGu!X9wn>7F~p_fbnq* zk@(f0gc)UN_p%k_2U0jjFBz&ae^=!P|Dip4?XfQrElxyDNr1(G^kT*!xhp?FEmnAU z_Ya@Dzzt7wrPybRvqjCPC8d5RLB9UE6HVPIzAH2(xw_J~ESWy<6AMK&%bX z0JQ}Au>IjSo$eS-Se|%%p)Hvy_uGh zqM?u}x2cjt-U2P(=FAjnC_C5GosSGDGW%jkP2?P!#nI?i=+;BMrtZ;bAVA<#5MZ%p z`*@bSA(`kjJK}8bwYdEVpiCnWc_I zpBO!lH7-QE(dgZ8shur|Wo&n*iRQx&`C&qoB_mo<_PyBbF(XGICaN%CrNJorGs5Yf>mRj%Yi({|@}G3C=Lk;MG5f1k0^?;?Tm-SWG|B+Cy z7MC1Kj#R>)lcTVwBWfK9;SPFhj*wKVS^IFvT+@M!d&G0n6|y*3f& z4gzPU-X-7Stm{7m4~~s+IJqPwW_Y8M30T=(OAbO(z3d6FlUIBeL2hV_E$LLRnymc!t3s^o5m9mYqSA z50Sev8a0eTUiOmN6EG^9XUfU-^5^K+3RLO@HkWp}6yD9zXzCc+6Ad&En|LR(_f5J5 zu&{5E^`-o~Z#pN7(U1u?D)U!6G4Ijn`B538Q1xHf#lM0+_keHVx_sYS+34F-DL{V% zj5xE2yuwoC6_%Q@rxzlBOM#}Z6(8*I?0ZQ5>ArRQyw0K^%b&C&vn8{)R3@z(Wn`9I z37xie@w)ZCb27g(Pj>rccIpKfVs+<%+8Lb8HhU+&UKC!-75R^zcNR+Pq)bs0(Q7V- zNWs?$e4Gt`qywio#;w~4-8dcIhm>I6x?Wh$Svb+dvaguF$o?{apa!}Saz2Z`7bG)T z#wT~%CufD*=wsR^ko74c){Bgvf?n>~;Y9W$wa*GIUT5FO@@13xQ|Y~!@2^-M<>GaD zz^iuGt}cQYQZoOOo#GIt4W1;nGI1|@`&iZPB8A@u$8di8Ygq1E<6i-0jgZLH63&E6 zu*WBe4|PE2AGU}%2@2oRYoK~#?OWStIg(dyb6P1ZtgKvzhlNJlX)y^k88xT zeJPOwoNE}3?!>tUcFtuis*Cr9PvG47&wW#+<>H6x>gA)+LnC)eFRFUa?|h`-8fiS+ z_@NKg70bT~rwnK(6)s|U(hG<1H&y5fFA={^#F>}F)A^T}29UKsj11$=qtTPGLfDcT zP#=qHk46uG)(qHrqtSK9v3f3WyWEPJt*H4vD2qkV1@Qy)@&e9k4)^Yl8B5$0lO`U0O#0KSkI735<4X1J+;2+qH^CZj*U!)@Y)!crc3Hc)|LSRujo7u-( zpTEy4x88R?+A*taSoWY8O@Vk^*jud_= zr4v57nf$Eu+Kg(eoGRzRf^k&!#&UaqcX%uyCjaaYFH}M1S@psLU|-M z6#fNtCyjf{1E$V;bpd?W@#xctYB4;K04t-A;>^xr{!}K@ndkdRjCsDtqCb3-1agqu zIuYLC11w@N9v4NH30CsM0Pkfd=J-e)(b4w;yocqyd=SvDP58Ddla?aumt~-w8s9tN z;mb2nn2wNEJ40r?X?8D2Q|C7&sGfcZ?B9>6?F6GclG`&NNkHx`xO&gdG8>c_JCxJV}RaHg)T zAmgI5O)HnV(HMUS$@vlq{#cxCXQlb#^+ZVK&odX(*+ zr*kvK&{^8k1MPxkpmRa5{8v>^b~{=0?79;MZ=3&ct{dJ%gU9C4drzxh_c-8{k~{}h z&g>Amej_}IuR?nmi{3XXM1<7&;tJ-C;zpwX7&3dw9B0rj{zyEDJVsbb#_OeY-$_+( z-X=ZmFV5cSf7WUB%ybu>*pwIWzjVWM*;bs@tMR;rzB3)uU9YKJ(^#}-bW@njyLRxG zuM_*VgFk!yS?B*8zDDfLdp>OQuJKN(V$e~S&9f!}6NgL=2G4;odTCnh$Ys5le-!?a zxH`IBsx zBen(~kQ=!p203Hg`;;vWd^r<1j%E`~W?(QN*Z$s)qk6Nnj(+5alK71o&Df2WC zrK{@?5xwz_v%=p<5l(&Bb9>?GR!}4t?{9E647m8F z%H$nV`hV5%T{VC&2^F*HlTh9H9aPA*xf~ki3DrNtV$Z)8348-Bo^8%4 zV&w_{(3bOV-=T<^YKHhRGkiVII+pfNocNTZu766^+r#R}^r44h`r-V~jl(I5#kdq- zS=r$z`E$;c6H9Uk zvadY~zxg@TCY!mkCFN^#i3JqsnC2taPaVjFaKab+5Z4v|CxeOD>q3v_QcGQb#&y$& zwy2%MVdF$fQ_00xa7`%-ym-%v}06uCoto!pTv z=)23aHTTv5o~Pz#L^Ai)AZlLsQutX1@WzE0rmpj0TwqGY*y#mB+_|S6WLQ5^?3!e( z=%*F0RR}};U<%*`9)PvqcwVb;z%u8`t|@&KK>f=c zirL+B_?3#gPjFYUnkky4{bXr#_??JZx7}eK(v8&i^TruNy1}~s{Ok4)kHw}BJpveV z%FRQ%^C`pnp+_B4U3R0ZUnqaRf*Yde$PhiBaw2~~5MZ^IR2_c4LOk(GgiBdl{=$Gk zKo1Oi<$!(Y4}gQU(kE&I?nQG@+kS#8TU+kvPjT!S<{oBkYAgOME)#Q(Ob-6Yw{Kt~ zw{}1y2t&H46(db|{gtgO!oduy^P%S&!;gpqUz)`Dm#&I04<8udCa%N$X<1(wUl$3d zi;sjii(O&8xDi)%m{HX=<(XkdF9l&Hr+6<1PPWsZ>S}eSvUA`6kx6a-92XtWm4ub+ zg>HeGFZl7@2EN_di0s5f{T7d9GdMl<_WB?88yuX6Nh=d{z|zhM?p52`{JWg#pBih8 zRWq8kdo{bw7BWy_qOH8rG-7KeHeHRaDS7IKo#!e^XnrNIUlquR*?MCB8h57EQ00m^ zm$MW$A6E@Mz{cdQnvf$(UEKU+2UTVdF$>|DD&%3QoZ?f7^{LvYm)!_onqbL5#FJOj zM_zMs;)T$z+7|zrEyTtdtu1`(6K>{b<`4;eyy_G5%qhoIt$AlPue9L&pX=hYWH`EG zsP^3JxW6!@5o^!Q#nZDxj{XWl3xy!7^9ogeXI!$mhc47&X33m4{+!ZCZ1i-|k7zV-ruL0Dj&ID@DN^S;kPV;7bw0<`# zgVG{Cv@|he%}|54O*i!@Rpc@EbsF&>(BBT_Y5^I?>k^P@-x6yYD)fPs6^6qZFQ+1d zJ2Tb|O*{3;SCGfHNV-e9%{y7)wB`gB8J>D$iSZuECojV(ARet(ogK$#a+8TWC98r>r&R$a7@lFuiCT)?BDl?lZnItX%9I z9=SlTpo{+Kd^|ubY?auU&&8(K{Lz^%!{bcTrMHjg?0=oGhnu;X!aYZ^}99pRzeis?^n)r?ep?XHcp&aC&;GOU+(a%O) zb29Ebf;?G)cM>l1b2`FkcsZVHam_}X8*wkFnSq()$X=WlXZH*|LOxLIfB z2b>wxK_R8XcI+T~6IEUw?HJJWdYlf)tyu%Unv%f2o+dFD7(D&QTeoGr+@%WAewFj= zS8+B%xlWzbHhsve{=xr-fBMk&;bM`RVf*e&tu7VeH}%A$Q$cG#AN7ca$KL*u?ZZOA zhNwqkUzT7lEDo~}cP0xp$Yhx!Lbj)zR-5+ZUdQZCs=TN6`8556XI?@>XrFJFGb@-` za|C?Eg;Tyqa7t5osNHu^)tk)X!+xslP|d#c1dM3uDBHg{Xip|c!q^~SO9T#AEl^-yIUats($zjZq(@E&Ay=6kX|{U}K%`mSsb*LPDPe|(yU&gV+sM)`#k`5ra= zadzB(M_to(-oQJNxc+%a8g>Tv1$fREq+O+Qb-8%jgeb}zo`VsJ)8XA7Zcb{DpCg1~ z-iQ5`enA-V&_&<)^^thlXW=)!+1lvQw{Yrp@*HyRCC}-vG>Xx>;OeRuZ+r2@AN=UW z7hk+%<1Zh3YzzL8EQQB+aj1oi^D(WOrBGfM%EC$tp<8sd0l@~Z4qxi|TX>^aK>U*j zPV-$Gy{oj&z(y~xnDOfc|2>|!!x8U-haZO2VP9J68+#+X|H22GknfFerhRZ%PElDP z$I^isJN+L2zr#y>tTa(}PtI(V6?AwbUMuM3+weVG?%oDlqIxI#`SZxmuw39(!lcuPD(aXqS2JCgHTI?zpbdh)4lZ?#@WP_ou0g zR$W>6v!M3)g2KB%(;I_KGp*^nqi`s6m0Ri)%*bhE9DL(0XMVtW?zM&$uG8wECqK}0 zKCR?sL~S&vv17c(^nl~y7p@hqWZ6XWKK8lZmf3e&ec6NW(^;4u0KW)Y{B-DLl_c8U zjVCTq(~Q{YRQI%|sqX1bHu+g+*I{C|%ltqkZSnaW&(53)d~cTRw2O4bN=vGyF1~GW?o4YtBs~L(#vFnQP58vaj8HlVCW?G>jB` zrldPjhcCaGr^cf#!?X`lMr!vW`qDVXof}-`1s3nhM1-Q^+;V(@AVc| z#@BiY?y2r4z3GFVyZ8{JlcDIXZ?}0f6*Jlpi^eSk5;B?QG(j>`oLva8`E137F9E?H zsdMXUn3keTXemr*AvUUP8cBW?=+v!AT9W=>>i=ZC{{6QRebrZ#I8c9MXJ&2Yb;#>n zW>b22o0I{+K`H*H!w}NfSW|8rj{Xb&oz&`Fycv$hVm5qR z!-2LOzS5ReP8KOy>SaTb!rr@y!Cv`XHw%MW(2G3}D6`G?Ke zUHmio*EewkqV@@=_C$tC2R8Rlr1>f}T@3%msR=r4wx+nPz3EKTgg#_h5=Y_G(43mj zn)fv0yv>No=RrB?GdCf=9mg50=7K7!TuZt6Gp=)!TbcyekDHydPMB2s^Pf5VtJU!F zF4mUY%fA|rE`hK5pS@fg|D+kKYqlXju9@4-1EyAIS%7Qhp2?`X8`?s2XlB#j!j~W! zvmFTE(zL@mp_c5#CdYShhodWi8MB;=)0V^04KbYEP&}9+^BI!>!vn+5!?@oKI%c?G zxGL++fz~0EW+)TW@?>3ba&>CrYbB`?wPd+-nvQ6-$1>bgo9Do~%fLmB%W!cD%rP)wF|w^cGN&RtWC6XXGPGu`AH_VvO4ClJi_Xs3G~?#lIuhoz0Vt%f@8$hfS2A5k2m|mDxG6yjp{q zeXoq79XtPGlMQC}y%zRM#4n0p`oynm@heZq9b=r()NPa3qC`lPEKtp|NfAgSq<5#( zAoC=0{DzehXmgOD9B22W71A#03*bRtKpjS0y>Hw>X5-GjMnr6kcV*Uo2;CGhM|Va| zHoij4V8{dv7geU?u=5vfx>V@A|5nAkH3NDbnWqojI``ZWaE~SdJjE=t_8vd`iV)7a zq3?yb*m(Gsg#)?h1;j$kdYs7Dv+QN6$CRqXudrX5^-kx|;0tn*FU`<__%p*cmUCk-~9@8Lyf=BkC zh+p9`3O^aAJRRp@Pe2lsJ0Lg8B+0cF=abK$ce}oa?>X-Z>>D0Dzoh2zK&B_%v$%Fi zT?4q3i5CJ_)?|8I=k(m0-dyL(P=;+`4Q*XimA03(5_#fYmf=K|*7z3jfX`$p1CI@< zPpeCCqW$XN0&9bp;SnchO{AzS$h5x(PpNm6jvlqTb3NaA8u5)n^|bnU&!?~@ItF+> z*(Dh^p*3wUk8FjxJl8sLFKunDN!{C8#V|M_GKXh4u3UJRO^BUTfDKFU80L&$OIU&nDoO z*qrC|nm^!t?VH}Ijyr>72C*$Yr`P^Ly#jBhIiNpy$SkHs@|ub6G}1gU5zghix-*%;QOGQJ=6DFWD>KAGc#O4!h3fQ#V>4igT7~+ym%^T37~1 z17=iPW%Gdac{| zD$B2!M2SY|3&3T2jcuS*t#TB0dt-pcIW23!J{#4IPF zWk7UZK$-7E?JXZYjHa~-}# zpE)B7ydp0qNfL_@!;7zF2lzLFyEONG8#CY#JrnI>27A=TYNuxA{71@U%(PBna`g_3 z_0%P=-U%K2->M355}pn*4(4i$%z<{9P++BT+;O_D9x^^ki}Q_8W*B59cuAb2R%zY^DU}#) zRAzz>Dbj*63Fg3_??Od84_N9p3_)dl7TQT;^{sT?1g1ARC%vA@PM z!;ovTByJ%7+mPpFvG8IaJRRbC^5+gEcswUBN+Nn?o&*1XuQeKT2(jCECR{|nWI~st z<$-_ZPPDCq`>H3_m*Xfx1BkUHKR+vQirLgJx{*~^zZ6|Cy!l+Kc ziyL-r1Kl09@nirv5)y$Xz#2IstDlE0gJ990(DH+ zZrJVH*B?V|q_a^T^bq*ec@1J{tnq}fgSi*4VG#l(9? z@!(N8akB1C)v#Kv%D8j8c@fN0rFSWZ_L569L=L?4^;L=z5W+r5G|{y3mdCCL&6( zlKx=>BPmu2YWZH zr0Xf}3b09ivuNHgxi!Ue>|qi~r;r~op3#cH!z?#UGjuqbI-cSs@ex^J`ZDz_{agC0 z`mp@B@~-C1DtN2lYC%{be1&45uao>Tpct`tO_R!?`-2f)J)SdbY=`)n84QgkR}P(c**XZCXdhw zh-vAH%Mxhq7E&RvrYXz1-sS}psGLBzp8IQ&SNeivR9FP4Ct*81I|8$Cf|)dl_mt%{<@)%vhy`+k0lCYyS+p1C!Ln1hZv_&dS;Rh+oiP!usDoE{uWBrCINmEhfm46W9 zNY7Y6_gxeZ>Yd8o&^;)Q;PyUnbas%qfEwtP(VdD!G>Ehw0T)$Z7YOuvf#4akb^r~Z ziV-A0Mutqm7(t|%C%lyXu2fy;vu|AIQ@1i@ewNR`7t460Uy#UsTJFP$dHIL@<|_@f zuS4HQBhR-QZWw3_c-O#aYV~0e^ED}%lXzx#N~@p0TqUl+|Q10g~}W!Hl& z?cj}OKziahB$t?{VI9sy|YwPK}*vO1j^RrgHM7%o09h3OtRq0Kho-YwK zU;Lra6=I+vVl{7A#SRpA5Twy}hv-*L;tN-yZaUm43Rf++FoRetQ_jYC)N?>>>ARmx zWr6+s195NDERp^RObt6`r%H|^2{DjT>M_0?hPsb^pTeO2i>TVpC85!;?UiW#q5>ccUKylY)l1{ z#FVw!X!uvL%(cRiKXr%QbA`zf<~j1(V__Iot}!DoJq(i_p(kGLjvqVe$y~eRhi-co zv^d-`Q}3&qQVA0!t)XXg^n|b7ajrAV_0(6ehrs_uC*?b~J8EFR4f{CkS73jN_(0f) zI#cc)g#9sce+~8lgiB%nqcfvb2zw7~0ql1W9tyhx=|f<@+37ypYMdOSi7_JKlq4peChzPE82%+}V zt`IR?rx8N!$*vF?T-6Anw$2se2UjIRsIBg%+bN(nxaoGh6LiCwrqG2#LuuFU*m<1F zm|>3UM$46gGbaTvbcqtIp@Og*&T#XC~*VNAM-^J z##adp4|%Qco!PAu64wWz|Fhn@lx9{KYACUshir?iB~gTPZSgzUFTJ7mtUCbvJvFHd z&V?6bDNY#0P4=04CHN}4Y zqUJ3~_r=n;bjRPTV=%|@D!rD;y6st$}0P+2U_Q3 z^`iSPLs9lRa4h8dLZBF_>~EM<_W*HeK3H`iq@rq_`q_r-{QIBpG2o^vMVb0(>#WRK z8J^HQ%dtXgTFL3bchNISWl5x|M67BlH$9~rZ4Nb0$*c<@%57D2FZTkZOV*htWkPOR z!6c^O9~1}bJ@Fbp&glqn4gwNAB%}weuwKA7?gZ7gs7uaM1n~Qg)%Ov$anC$_-vKX6 zBM@#c;B0*Y#hnzj?037XCaN9c1OAy{%02>$P7eAHqqOSN$II zz|8X@`6e&ZdnQ)-lFc37-awQQS;`W*-UQB8k*OIJ+jBQ#Y1Q427q`^EXOPFdQ!_E_ zU439?IPV|NDHqu2zIIL9vX6bTBoP`()DWd`XYv_YA%F8q}a$H=a5s@0qyn9&Y7J`p(A z0a<|=0eXs)x)U`g&y?ypeX5>QNc6oGoAS+i$~FC3kJAjJIWJa`!b_i!>(TGKs7z~W zs~Nq~P)*-IeKnELJ9>a#ry?*xFtps1pKIAqTx-g3|A_6|CS!gffxP;N87K(Be=6LD2|pdMtgHbR1L%^QAYQOuxc7DtK@BWNjGhoDm(VDoCoR( zR(Q5>o{yLC$bDM2RA6;5Km^Bm;D0IMJFc{YU1@(t+UEQ2uVJO;U{oN+kEHv`4r8HKSc$(V*SDH40t8m`UG zxQZ5=WV~cs*SBwMdwmMpYzkrzSk&WiE`et@;F&SVkG5QjRy^GG>`7|`qnzP` z-_TOjz0C6}iQSGIV=~xL7j2Oba}z`)LOR%Nr3lJ??dxs9x^*}Z>V*;{SwesZ5n@(k z_nGsf3=q#ad)EU1@LRVCTikjW!A5(g-*vpujC4@%bU< zCV#_r8uk1&%vFr9wBA=?@B9V)U%{M#`4XlBaedz-k`$P^Fq>dLf%y@}XAhCg(9O&Y zDm808OJ|I`&Tp|m5-f^93UvdYs*15Zg?bGsor3or;B$4`d5tW@yq!;t=b9O1xq3A? z5U-#gP~N57G7hPL?_5rO{-q>lrM1M8iLlK)4bfQAb?F(wrOYU%xpwI!^wSr3%1h+R znWT-d3zc%?g3?jhds^1Ax$4{$|MKg+WGi^IrGoNY=m>7$+1=QYcpfN~oA$40Mqg)@ zS7gbin3W4wy4}y4Vpc5Z4nJ<%zp}YId>}6xd!RHoZFmDM2SxnMwM0B$@O*|A&xN0r zftT(_M}g5i4P}SAa|0K1>`hykZUe6c9YRV$2YgEu-y2lWDnd)w*eZ}4i8a-_zg~{m zV5%S1NMg5H{W4wvCyKUGw{9V)pgc5MKeWDRUD5g(1^RD;*#$%E?ccCzofX0sy^nf= zP3!VD?D!*szTVo6mHn^GLs{qY{+R~sTz~0gE9Pr8ZM#bdmvoH}kZ9A4w z9$;k`P6;C=x<25X9P1FfRt`YYg5LxBHQ4J8rE(EecH|el#|l#qLvai=;rAWcUD1$B zrrJpa`vJq=K$Py)=j=LP>?4U6 zc;V7O$Z|lBylfU$Nb5Tp+-b6E`gOi?cYRuV!*TF3Q>`QTP$F!;Al%(LKc2BibkJI{ z@N}#+v@`Za9hfJVnyR*_qiST@8I7OyA??cumhoX>SE?Y-dq1T~$`JS@ z`wU@{RD^%~MT>+n7#YLnA9&?WJHkS$A?M1k^~xt56gyzp4Zi?Ber00c9?zW z2VEZSlcAbM(8YxM``5SMj&(ZzRzvw47%5HXgVKSfOqAQRWkbLfW?s(-)QSvm0qX{( z9Efk6xixcZwgiQh_CeD zs_ui^B%N#SHc*VVt>8`Jgmvjw^>4K?rM@vLd%cNKMi>$2_ZIX;duf?rRvV*4nk8=m zS?gCDZq+@tG%P4az>7|)T0bx;OMQWHZ-guWlLScs<&9as(Nxx)gwM~o6tY>Js8zLA znoiGR5}@50d(Wo)TR`j+^-MU^!QEk6WPZUa5`EKJjl4fq4{MM{5XCb(vISc3iQ9PA zrPttNm6y)Q+{QDFGiNC~eC}-Hxkf2uprsu?*ik}1q(YF$Byq8%>}N>L#kWsH>-@qw z9d)}B5~-$kX$3*8E5VmyhJS10?0<0mWB1qo6I>cU-+%_$5PzW6{kuffdMok9>Kwbj zhaY5Q=-sX|Ewtgl2bXK5yW-cEtoN?i!;>vHS7YX4IdCz2%H>93BksuM+O0knAx1{& zTMoK~%i)4#FY0MF*0<&AvG8Gt8Q0hCFt(AjDPCxKmq*@yr)6p=X zlp7pk4Sh&cO8q|`d5#SJ(b_xa7ShQFLmE#TOKS*keoG4tXXHX6B5YJ6gt3aVdI3vD ztP3{DDnen)%0mruy$dt%HQFa>-&~KjN5>7?KLao}9EY3WXc_B1&Gt&F%`4s)9I*pb zy?4K|g?L0?L%-z%v+B?s1%5vwk_;UaU!`a9;0EJ zu*_2@-Y+N%tAOs{Ivx7Bxhs(NgLRlsFkU=bCR(1#yKlJU>fSIWMvbgV1nv=TnYFub z*rmKc+HX$X`9cYF8A$BN>QCMABwj|wo`6vd(l=eiUfv~xYdP)=c%E07DFFkc9MfqWkG)b1kHkrteHs4sBlf-bBol4{ZEiQ`gPHI+<4IE2O<)u=*V6QA` zhFmYrav9SjHrz~7K&%4Xc6zeU15cW+#VbKeJ^q=W6#~?c;FPdMqa0*5_)u! zN?A85#x&%uf+5QIBf)r@M0%ji-Nppl=;12wY1E0|TKD~r@z^8N@(qQFhZzZDM;*}n zG?h4k;4agVdvT`%BmQ~ZWJhH>B-M~+alNzCW=36%Jkm$!jU7FS9ePC&mFSWYtPDkn&}uRCH2* zSr>hh`hz-|q0KgWkMd31$P@J4jPe@^13h4hUb1eM7w%_f6tos7Pjq7?P8gIYvP4?i zYR~kvT48mTdp7aa9?dq{H=F2ps_bSHz4MLnJgmFUH@*;BdYvbSUgd-05Awk(db`O% zzK;s>$Gb_y4xW|m;JGcYN^+tFEsP+uiHSbQ_fovd2TtI&N7tXd<3WJd*7Y9R;0j36 z=RSBBuEA)RL!HrDq$HxfPRDzY1mh|Qc2S#6$$TKV0}Q)V3ZXyFGRiVlATJpt z*9d`@o`D-dd$HavfzXOx+tp}!8}D+)1>w|FjJ#H1MlA+5wmB=24~(aBCV}yi16=b( zP6#|brbBpF&I`i4H5@R!#DgR)tfayv8!-h42_)7~`+Sz%%p_G*`NYai&(#x!dzNxK zOpqz0x>ZX*_OB?hEY+2@yVfYJerx3|CSPC38ZOG3sXjl;AEP4aUj)kST}vrv2Il>y zcVR3&lmpGMuEPy{IGI&7acHBS;PEnoSNUF`Y*4()E?T?JQyxqGs@9vP>D_mp9JOuJ zny@}6W$)Qs^&^>_HF+E@t=tr@rF87-QUI+O=aqNlnpizEG+lCwTUiqb;1Tp#c*8X^wjAXrc@8M1HL_+N^!w zof2p!%Nn2L*@|kUoYFvf$Bk+Cpdr9WX^bHGBu^Sk(sWnJpv+o9bb13F+f%Jx5kVN& zJ;4X)aFpFuP3#1Zj8pXxChN zxLcNN0c6QiTFr@W>6P1cxZ}7q*_fnH0QclaTcQCgu*Tf5!I{3XNqUB78|xeV!Sy6% zF}ms6P_wMu>39(c$4Pn;b*^@#@vO}cGk<@bpKInf9}3rz$i8OE=_N`<=0|E-1Jf)F zgDl%BTPXYHf@Z0hdlUMMr5ebx9aHx^&kXz3c7o52_bm^Ijj9Py9>N+qNh>#@kBlqB z>FnT*gDpNg!Ozn(iLznPqSkiUTyv66=w9Et=5;zB(fNe7CEDI7{b+lm^rQTx7b|ya zUjT2(7t-Bj_x+%$Bh@N!gD}M{I?i)_1F!j%M``6o-|}#6FZ~HV19~8&RJcu6F4!i@ z!dhZmBGwX5I7RfGFS*web=~jafxbX-0(u+B;1p}pJWcfntzHR&=qE8dF?Q(~Mbr>7 z6SqIzv5p4*0KKv9cPoE_#jaZP z3$S0<-swmLntDOe4sO{C31lxuK%1P|7YG?(0Zvi{$Q$>!An!&eMRle++`o6fMfk{DD4M9i@IK^v z)`2>q$o8KgC)1Fsk|Z2f9kL$F2NX3A&v zcWe=`J8YcccbmU~Gq83mtF&7=xrWmdASfG{7>aB{YT9n zd!%Nu;|6MlEW#Uz6(k(`YryhjK_vz??B&9)5LN)Y0(D*u1PF>;(doE`yDKPi1tFZ4 z0eW)$5mELlK=+A10Y2``(^d0Tllch63r#Y`9Xdwg+kFq?_HZf{p~EiH?t}XknDPMV zF^BL}k5Q(g8q4umHTMA~^GlTzfwacpJ%y0QMoPHWw$t}f*P`||U~SNyz=ldjOHoZi zfe0TC7mX7lmAkH@v^PLeJ?w0p;5l`)_ zyqM7T=iLH+csRwMLkqr2`5IIbApV5sppM!DD`$!wE)1qlhqjYMwOsz)=84mVmywI& zB;AovL;*e8$0qczlQnx*Qu)X|OR=+vfCe>6<$dxYUH8&=0L26dxt)$LcuH08Xg6KO zuDgZ;F%EK9dgv-hYO{7i&y0HvyH32Lhn@mRjr_Y)GHzsbyF=BXsE#tIEF93DxyC3L zhSN-7XzoaNA&`T9ZrqLjF4-VAF2t!jU*)bz?iI^ueZY@owX!Q-89^zGT4>E_Gcmy_ zeyQP*ACYJ!Crq)OKwUh;OHKe=3fl5*wJG+$O>D6_oofi_B@Jt`PU>3|)>NCj4eO;c zn8ntRRPc?ZDmJKQc2i1tUuX=G0!`BdnWkx?-|kK(L24%|%U$C8WKAYXX*$1TCQ&sp zB)?@1`yi%I{h<~hk2as4AgRG9ON{AT?8FyOWJ_u?+3cnX3RTlY#hTHlYwB8@oT};c z1Zd{B0jm)^Rc7?lSN$=$tY3Oy64)*@+rUasDAtbjc8yYr> zrmIF{`ZnZ`^x15Uih$Sc%ZzTfQqDse!Wmb1Ch?=;$?aCk2YSsW?fzQGv*3F@t?@_| zRFi=J`dWNB_5}3pwA{UG@Sh{mZiO2rC%{Un#MG);-&*=CSE~b+K<9_gsq9@U`aSq6 zmrDhg3Hh;&q-HJXuO|H{Rk>|IR9n*&QM{%}Sv=ngt@`}BW_iKqHFZHLsti?%>S)bO zbui@9F$12d4$! zpTomM{SSe!P}M9&JxJ~QYY1w1k~&E9S&dZ{q;c26T9isuV?tS(L?-!&EeGF8zcHwW zeq}gl$N37Zw7w*u87SPu_=Z7}(U|UUUy~!KRgtI~m5cWNEoA8vHRLX(BmD}^L#iUb z{9bq(ITkQlH7lajRMMPOZ6>6q?FhWs8c+>dwkq}PCL)!9iW>VH8j9acNLV9IWLX+U z(|RIpj~|o;y;Lroh}q}?Y|VO%5Re(Mf1;7p>}dgN_g%t$*0HHoGI~$*>0H?r25qt+ zm9|XULb3ACQ2=W|)69~d*3TlGrlRo^nzCtY?umD`UN!Nlt7_@W@j9Pl-^Cqj_RsgY zkkdqz8k9xZ!P;G=#CQ3(s)zJ?LO3_@Zt>}g0$Us{Po*x3{4)(}tFdU(8GpYkUJ97$q| zB*YsweSr_Pk)bcOZ{WQ$*ryr7QhPl|IBFv!0c{DOH5pURybB7Th*u-ND@rC^rYEUzPNEY`alG_n( zx>ffll9$4XB(h{kWC_VEEG|+^&MR4fhulAku|sJ@=L1TM9$N-KP4Pr`d}_CU-lBQS z$h@UXhQQ2TzNo0wSX8jAsBm7%QV{-$MT-~ZEi8JHOj%g8ki^U>UYxfqhD0q|UR)fF zye#91gc_P}b+_#~VcO8loY9JsWqC`N&093rlZ;CnH(D`gX;G0Pa`_-dao*CoMJ3DN z_9T%do}_Sej)`1ON{W^#3XAfW&viY3+GSDWD!fuc{An8y z`*?(f`Uj32J3OJkGA7RW+}~CdFUT*-$kC=u&YkgeqwV+G_kr11fBjPJnJ>Qi*OoVT z?cDUr3mf)+{P%YcA3Ap8t5awHedX%KIw#+9@8(axHGNuHee%GEAH4UPdF_j3ufJVB zP!T;i`H5kP{et{@aRP78sS~C@qsvZHFE-@ODOt99<;Kk~nYM4Mc+2uh&C!GV_q^ZU z<*@(!WAm?{fBD_l*DjyG00QWjFMWR1#HVIY8<(X?4er}pCS<*&;RA+5jTxOZbbO{N zebSU!GoM{jx@P{u!h$D9#gB-H926^JB)%bi0^}d<+x?HKBcC0AW9yE0UVe4`x*r;> z-=F^Hx94u%_~nm|2W@vAcH%^mGC?tEnqt|!g++^(FC$MXCQKctC|Z=4UtCn!?L(!y zy$K~mvJd7Uj0NThOf}5AFdx96I#ppZRz=$p8NP@aMD3oR#2rWb8;t{x@Xw#X9Y^~n zjf?v;#^s{nG*4>x7}|fSo90Iijd$fe4UXM3fMthL3x0=X*c z%*fKG|37IH|EIK|RL1PdY1wJx(k4%u{$C4=BFua|)Bje2k+W&mE<$w|7pakjB2JN` zqhw28yiDyE}hx z}ha_*#wIpfFavNF@Psp^!mW0FUW7@9aFE@q%o5f&u(c6~DajQ{!@(jEIo zy!g36c|N}%o9MAK_{>7_Yi;w5!#*guy=Qyju0-<{pZAYmUD5aU#YS^O-J7x5pLm>D zW%-*p?x<~RpPDU&vQPW8Dk|q^EUCWpL(0kZt1ny*Y5wWj!ih&Nw0*VV{JN)h6w6QT zT~N5PJ^#V4XNz9WnZ*P&6pIQ9#`t#J^_IN)wPI27GqQQvKc(m|E?qMBz1p9+C(&x)2@VLnsT?TC?G{A1$=%aVRaJ`sKJQ_VX`7moh&-dSeGZmv%*eErG!3%&Qwn7`8NJD;E4c6yWz{D^p3c8OP~migN2_DEhbv@(6W zPK)L}JvHBPZf=oj$?)P}n`ptJXG1S^HO8LbIAi5y*|%BO<}SWo-QNDk$<3ORpZ31E zxl;ejo=cbhR#yA&nbY+nC$(PBX_A{(en#WUOv@RmSC5@A~Xe&yVkAal`d1 z1u0+rp}#)m`rN&LY+jVG;^aK-rbBt>Le|asYn zaLUQ#WB-iuI#IQ4#^G4O{6n+;;r#w|!gtmquk30V)aRogW>%gqtQgQ*@atQ9<}ddw zTgdJcdAv1txKHzjx#FersYLifR?YT+l}CU4DAw})$k0!u6`Sj}d7r%a^QV7YT@`-) zir0m@^DnA@ywJiQx@K6k?sC6>^*XtB=78#ZH=e6p{9O8{LAPc|%*Oe?&To=Mb7pyg z_p+<#wRs=q^XHul^3uL5?p6Au=kDL@yuY8kPB8xTA#POOfVuy0^wL|$rO(T}^4y{) zv*y=+balq1hB;o>Rrcii5xF0Iw(p<2j{mUcyQ=it&Li<*ttU>reEQfo@nwf{|GwvN zf8lWJu`<#3|B9aa!{nN|4a&hQ=Nvkkm3M{>H9Y-#?BbXaC%q28yIJ~0=ylaji!%#sBqSp}^I8MB$ECK_H>W{rD4-w_R(T?sSjGVNvf|=MSU7Si_K!jLHLR z1JB*v>yk&3TmK^eKa;4)1g@tH*oHlH|CxfitkA>XLVD6Y9@kTz;WU_*Clx#cl!x2> zpXvS=zY3Qf^}Gl4dFX!pSxO%T_J5Cu_W0cN89}|YJQ+k4g7Sp!#+=rZq}#UA{6ndS zRpHO|W5NjL8CK=;;E(M?AYjI-;B@`CzSyG>R^{^GPtcE$34~R_>G}y3n2-poBHcex zI3cBkRdsuDB`L~|dSMXoER1U+#TxEwA{*F~=21I?IGvCBoezJHhPvG}PZcV{iA|v^ H8T|hTn0)s@ literal 0 HcmV?d00001 diff --git a/boards/ark/fmu-v6x/firmware.prototype b/boards/ark/fmu-v6x/firmware.prototype new file mode 100644 index 0000000000..39718c37a3 --- /dev/null +++ b/boards/ark/fmu-v6x/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 57, + "magic": "ARKFWv1", + "description": "Firmware for the ARKFMUv6X board", + "image": "", + "build_time": 0, + "summary": "ARKFMUv6X", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/ark/fmu-v6x/init/rc.board_defaults b/boards/ark/fmu-v6x/init/rc.board_defaults new file mode 100644 index 0000000000..ba812e4b7b --- /dev/null +++ b/boards/ark/fmu-v6x/init/rc.board_defaults @@ -0,0 +1,21 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# Mavlink ethernet (CFG 1000) +param set-default MAV_2_CONFIG 1000 +param set-default MAV_2_BROADCAST 1 +param set-default MAV_2_MODE 0 +param set-default MAV_2_RADIO_CTL 0 +param set-default MAV_2_RATE 100000 +param set-default MAV_2_REMOTE_PRT 14550 +param set-default MAV_2_UDP_PRT 14550 + +param set-default SENS_EN_INA238 0 +param set-default SENS_EN_INA228 0 +param set-default SENS_EN_INA226 1 + +param set-default SYS_USE_IO 1 + +safety_button start diff --git a/boards/ark/fmu-v6x/init/rc.board_sensors b/boards/ark/fmu-v6x/init/rc.board_sensors new file mode 100644 index 0000000000..2b66a4d021 --- /dev/null +++ b/boards/ark/fmu-v6x/init/rc.board_sensors @@ -0,0 +1,71 @@ +#!/bin/sh +# +# ARK FMUARKV6X specific board sensors init +#------------------------------------------------------------------------------ +set HAVE_PM2 yes + +if ver hwtypecmp ARKV6X005000 ARKV6X005001 ARKV6X005002 ARKV6X005003 ARKV6X005004 +then + set HAVE_PM2 no +fi +if param compare -s ADC_ADS1115_EN 1 +then + ads1115 start -X +else + board_adc start +fi + + +if param compare SENS_EN_INA226 1 +then + # Start Digital power monitors + ina226 -X -b 1 -t 1 -k start + + if [ $HAVE_PM2 = yes ] + then + ina226 -X -b 2 -t 2 -k start + fi +fi + +if param compare SENS_EN_INA228 1 +then + # Start Digital power monitors + ina228 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina228 -X -b 2 -t 2 -k start + fi +fi + +if param compare SENS_EN_INA238 1 +then + # Start Digital power monitors + ina238 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina238 -X -b 2 -t 2 -k start + fi +fi + +# Internal SPI bus IIM42652 +iim42652 -R 3 -s -b 1 start + +# Internal SPI bus ICM42688p +icm42688p -R 9 -s -b 2 start + +# Internal SPI bus ICM42688p +icm42688p -R 6 -s -b 3 start + +# Internal magnetometer on I2c +bmm150 -I start + +# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer) +ist8310 -X -b 1 -R 10 start + +# Possible internal Baro +bmp388 -I start + +# Baro on I2C3 +ms5611 -X start + +unset HAVE_PM2 diff --git a/boards/ark/fmu-v6x/nuttx-config/Kconfig b/boards/ark/fmu-v6x/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/ark/fmu-v6x/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/ark/fmu-v6x/nuttx-config/bootloader/defconfig b/boards/ark/fmu-v6x/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..c74d5c18b1 --- /dev/null +++ b/boards/ark/fmu-v6x/nuttx-config/bootloader/defconfig @@ -0,0 +1,96 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="ark" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0039 +CONFIG_CDCACM_PRODUCTSTR="ARK BL FMU v6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ARK" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_PTHREAD=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_LIB_BOARDCTL=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART7=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART7_RXBUFSIZE=512 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=512 +CONFIG_UART7_TXDMA=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="bootloader_main" diff --git a/boards/ark/fmu-v6x/nuttx-config/include/board.h b/boards/ark/fmu-v6x/nuttx-config/include/board.h new file mode 100644 index 0000000000..e4146c3237 --- /dev/null +++ b/boards/ark/fmu-v6x/nuttx-config/include/board.h @@ -0,0 +1,558 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6x/include/board.h + * + * Copyright (C) 2016-2022 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_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 px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The ARKV6X board has 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() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has 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 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#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_NSS_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_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS no remap /* PC8 */ +// GPIO_UART5_CTS No remap /* PC9 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* 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_1 /* PB13 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(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 ADJ_SLEW_RATE(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_2 /* PB9 */ + +#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_PIN9) + +#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_1 /* PA8 */ +#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_PORTA | GPIO_PIN8) +#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 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* The STM32 H7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 H7 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 + * PG12 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 /* PB11 */ +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */ +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */ + + +/* 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_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 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_PORTE|GPIO_PIN11) /* PE11 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_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/ark/fmu-v6x/nuttx-config/include/board_dma_map.h b/boards/ark/fmu-v6x/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..f1a94934de --- /dev/null +++ b/boards/ark/fmu-v6x/nuttx-config/include/board_dma_map.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * 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 + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */ +//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */ +//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..d7d30f72c2 --- /dev/null +++ b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig @@ -0,0 +1,295 @@ +# +# 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/ark/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="ark" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0039 +CONFIG_CDCACM_PRODUCTSTR="ARK FMU v6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ARK" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_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=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0XC0A800FE +CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_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_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_ETHMAC=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PHYSR=31 +CONFIG_STM32H7_PHYSR_100MBPS=0x8 +CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32H7_PHYSR_MODE=0x10 +CONFIG_STM32H7_PHYSR_SPEED=0x8 +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI_DMA=y +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_DHCPC_RENEW=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_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_UART7_TXDMA=y +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_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y diff --git a/boards/ark/fmu-v6x/nuttx-config/scripts/bootloader_script.ld b/boards/ark/fmu-v6x/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..5b1bb4cb05 --- /dev/null +++ b/boards/ark/fmu-v6x/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2022 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 ARKV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The ARKV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/fmu-v6x/nuttx-config/scripts/script.ld b/boards/ark/fmu-v6x/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..d06a7d7aa7 --- /dev/null +++ b/boards/ark/fmu-v6x/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2022 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 ARKV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The ARKV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +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 + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/fmu-v6x/src/CMakeLists.txt b/boards/ark/fmu-v6x/src/CMakeLists.txt new file mode 100644 index 0000000000..c84d6f291c --- /dev/null +++ b/boards/ark/fmu-v6x/src/CMakeLists.txt @@ -0,0 +1,71 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + mtd.cpp + manifest.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/ark/fmu-v6x/src/board_config.h b/boards/ark/fmu-v6x/src/board_config.h new file mode 100644 index 0000000000..12d526f142 --- /dev/null +++ b/boards/ark/fmu-v6x/src/board_config.h @@ -0,0 +1,524 @@ +/**************************************************************************** + * + * Copyright (c) 2016-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 + * + * ARKFMU-v6x internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* 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 */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks +#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid +#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 2d // 2 Digital Current + +/* 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 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* 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 + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + + +/* SPI */ + +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) +#define GPIO_SYNC /* PE9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_100MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define PX4_I2C_OBDEV_SE050 0x48 + +/* + * 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 ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(9) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13) +#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PF12 */ ADC1_CH(6) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ 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_ADC3_6V6_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL)) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS4_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 + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ +#define BOARD_HAS_HW_VERSIONING + +#define 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 /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 +#define HW_INFO_INIT_PREFIX "ARKV6X" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 // Rev 0 and Rev 3,4 Sensor sets +// Base/FMUM +#define ARKV6X00 HW_VER_REV(0x0,0x0) // ARKV6X, Rev 0 +#define ARKV6X01 HW_VER_REV(0x0,0x1) // ARKV6X, BMI388 I2C2 Rev 1 +#define ARKV6X03 HW_VER_REV(0x0,0x3) // ARKV6X, Sensor Set Rev 3 +#define ARKV6X04 HW_VER_REV(0x0,0x4) // ARKV6X, Sensor Set Rev 4 +#define ARKV6X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0 +#define ARKV6X13 HW_VER_REV(0x1,0x3) // NO PX4IO, Sensor Set Rev 3 +#define ARKV6X14 HW_VER_REV(0x1,0x4) // NO PX4IO, Sensor Set Rev 4 +//#define ARKV6X40 HW_VER_REV(0x4,0x0) // ARKV6X, HB CM4 base Rev 0 // never shipped +//#define ARKV6X41 HW_VER_REV(0x4,0x1) // ARKV6X, BMI388 I2C2 HB CM4 base Rev 1 // never shipped +#define ARKV6X43 HW_VER_REV(0x4,0x3) // ARKV6X, Sensor Set HB CM4 base Rev 3 +#define ARKV6X44 HW_VER_REV(0x4,0x4) // ARKV6X, Sensor Set HB CM4 base Rev 4 +#define ARKV6X50 HW_VER_REV(0x5,0x0) // ARKV6X, ARKV6X Rev 0 with HB Mini Rev 5 +//#define ARKV6X51 HW_VER_REV(0x5,0x1) // ARKV6X, BMI388 I2C2 HB Mini Rev 1 // never shipped +#define ARKV6X53 HW_VER_REV(0x5,0x3) // ARKV6X, Sensor Set HB Mini Rev 3 +#define ARKV6X54 HW_VER_REV(0x5,0x4) // ARKV6X, Sensor Set HB Mini Rev 4 + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* 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)) + +/* PE6 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 + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#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 9 + + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ +#define BOARD_NUMBER_BRICKS 2 +#define BOARD_NUMBER_DIGITAL_BRICKS 2 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ + +#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#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) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* Spare GPIO */ + +#define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) +#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true)) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 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 1 +#define INPUT_CAP1_CHANNEL /* T1C2 */ 2 +#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN + +/* 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 /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * ARKV6X 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 (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) + +/* ARKV6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0 +# define BOARD_ADC_BRICK1_VALID (1) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 1 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 2 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 3 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 4 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID)) +#else +# error Unsupported BOARD_HAS_LTC44XX_VALIDS value +#endif + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS4_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_PD15, \ + GPIO_SYNC, \ + SPI6_nRESET_EXTERNAL1, \ + GPIO_ETH_POWER_EN, \ + 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 PX4_I2C_BUS_MTD 4,5 + + +#define BOARD_NUM_IO_TIMERS 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/ark/fmu-v6x/src/bootloader_main.c b/boards/ark/fmu-v6x/src/bootloader_main.c new file mode 100644 index 0000000000..8c2ab001f7 --- /dev/null +++ b/boards/ark/fmu-v6x/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * 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 bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/ark/fmu-v6x/src/can.c b/boards/ark/fmu-v6x/src/can.c new file mode 100644 index 0000000000..f4c59012fb --- /dev/null +++ b/boards/ark/fmu-v6x/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * 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 can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#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_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_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/ark/fmu-v6x/src/hw_config.h b/boards/ark/fmu-v6x/src/hw_config.h new file mode 100644 index 0000000000..3a0205c87b --- /dev/null +++ b/boards/ark/fmu-v6x/src/hw_config.h @@ -0,0 +1,128 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 57 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/ark/fmu-v6x/src/i2c.cpp b/boards/ark/fmu-v6x/src/i2c.cpp new file mode 100644 index 0000000000..eb200ca932 --- /dev/null +++ b/boards/ark/fmu-v6x/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/ark/fmu-v6x/src/init.c b/boards/ark/fmu-v6x/src/init.c new file mode 100644 index 0000000000..9032b1531e --- /dev/null +++ b/boards/ark/fmu-v6x/src/init.c @@ -0,0 +1,282 @@ +/**************************************************************************** + * + * Copyright (c) 2012-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 + * + * ARKFMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + VDD_3V3_SENSORS4_EN(false); + + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + VDD_3V3_SPEKTRUM_POWER_EN(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SENSORS4_EN(true); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +stm32_boardinitialize(void) +{ + 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(); + + VDD_3V3_ETH_POWER_EN(true); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS4_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + 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"); + } + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + 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); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +#endif /* CONFIG_MMCSD */ + + return OK; +} diff --git a/boards/ark/fmu-v6x/src/led.c b/boards/ark/fmu-v6x/src/led.c new file mode 100644 index 0000000000..7730150731 --- /dev/null +++ b/boards/ark/fmu-v6x/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * ARKFMU 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 + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#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/ark/fmu-v6x/src/manifest.c b/boards/ark/fmu-v6x/src/manifest.c new file mode 100644 index 0000000000..6b8405bcf5 --- /dev/null +++ b/boards/ark/fmu-v6x/src/manifest.c @@ -0,0 +1,223 @@ +/**************************************************************************** + * + * 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_v0600[] = { + { + // PX4_MFT_PX4IO + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_USB + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_CAN2 + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, +}; + +static const px4_hw_mft_item_t hw_mft_list_v0610[] = { + { + // PX4_MFT_PX4IO + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, + { + // PX4_MFT_USB + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_CAN2 + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, +}; + +static const px4_hw_mft_item_t hw_mft_list_v0640[] = { + { + // PX4_MFT_PX4IO + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_USB + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_CAN2 + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, +}; + +static const px4_hw_mft_item_t hw_mft_list_v0650[] = { + { + // PX4_MFT_PX4IO + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_unknown, + }, + { + // PX4_MFT_USB + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + // PX4_MFT_CAN2 + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, +}; + + +static px4_hw_mft_list_entry_t mft_lists[] = { +// ver_rev + {ARKV6X00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, + {ARKV6X01, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2 + {ARKV6X03, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 3 + //{ARKV6X40, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // HB CM4 base // never shipped + //{ARKV6X41, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2 HB CM4 base // never shipped + {ARKV6X43, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 3 + {ARKV6X44, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 4 + {ARKV6X50, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // ARKV6X Rev 0 with HB Mini Rev 5 + //{ARKV6X51, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2 HB Mini // never shipped + {ARKV6X53, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 3 + {ARKV6X54, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 4 + {ARKV6X10, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO + {ARKV6X13, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 3 + {ARKV6X04, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 4 + {ARKV6X14, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 4 +}; + +/************************************************************************************ + * 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() << 16; + 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 %08" 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/ark/fmu-v6x/src/mtd.cpp b/boards/ark/fmu-v6x/src/mtd.cpp new file mode 100644 index 0000000000..e697ddc9d9 --- /dev/null +++ b/boards/ark/fmu-v6x/src/mtd.cpp @@ -0,0 +1,128 @@ +/**************************************************************************** + * + * 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_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(4, 0x50) +}; + + +static const px4_mtd_entry_t fmum_fram = { + .device = &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_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 2, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 248 + }, + { + .type = MTD_ID, + .path = "/fs/mtd_id", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 3, + .entries = { + &fmum_fram, + &base_eeprom, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mtd_mft + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/ark/fmu-v6x/src/sdio.c b/boards/ark/fmu-v6x/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/ark/fmu-v6x/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/ark/fmu-v6x/src/spi.cpp b/boards/ark/fmu-v6x/src/spi.cpp new file mode 100644 index 0000000000..2d047cff1d --- /dev/null +++ b/boards/ark/fmu-v6x/src/spi.cpp @@ -0,0 +1,86 @@ +/**************************************************************************** + * + * 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_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { + initSPIHWVersion(ARKV6X00, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {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}), + }), + }), + + initSPIHWVersion(ARKV6X01, { // Placeholder + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {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_all_hw); diff --git a/boards/ark/fmu-v6x/src/timer_config.cpp b/boards/ark/fmu-v6x/src/timer_config.cpp new file mode 100644 index 0000000000..928f4916f0 --- /dev/null +++ b/boards/ark/fmu-v6x/src/timer_config.cpp @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH2 T FMU_CAP1 < Capture + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_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::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + 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}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/ark/fmu-v6x/src/usb.c b/boards/ark/fmu-v6x/src/usb.c new file mode 100644 index 0000000000..92b6d33eb6 --- /dev/null +++ b/boards/ark/fmu-v6x/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 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 ARKFMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +}