From b2c8f0539e11919a690dd9cb749883827ccb1696 Mon Sep 17 00:00:00 2001 From: Liu1 <108582329+cuav-liu1@users.noreply.github.com> Date: Wed, 25 Sep 2024 23:47:35 +0800 Subject: [PATCH] boards: add new cuav 7-nano --- .ci/Jenkinsfile-compile | 1 + .vscode/cmake-variants.yaml | 5 + Makefile | 1 + boards/cuav/7-nano/CMakeLists.txt | 34 ++ boards/cuav/7-nano/bootloader.px4board | 3 + boards/cuav/7-nano/cmake/upload.cmake | 49 ++ boards/cuav/7-nano/default.px4board | 87 +++ .../7-nano/extras/cuav_7-nano_bootloader.bin | Bin 0 -> 46948 bytes boards/cuav/7-nano/firmware.prototype | 13 + boards/cuav/7-nano/init/rc.board_defaults | 20 + boards/cuav/7-nano/init/rc.board_sensors | 29 + boards/cuav/7-nano/nuttx-config/Kconfig | 17 + .../7-nano/nuttx-config/bootloader/defconfig | 95 +++ .../cuav/7-nano/nuttx-config/include/board.h | 554 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 71 +++ boards/cuav/7-nano/nuttx-config/nsh/defconfig | 327 +++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++ .../7-nano/nuttx-config/scripts/script.ld | 229 ++++++++ boards/cuav/7-nano/pwm_voltage/CMakeLists.txt | 42 ++ boards/cuav/7-nano/pwm_voltage/parameters.c | 44 ++ .../cuav/7-nano/pwm_voltage/pwm_voltage.cpp | 56 ++ boards/cuav/7-nano/src/CMakeLists.txt | 75 +++ boards/cuav/7-nano/src/board_config.h | 408 +++++++++++++ boards/cuav/7-nano/src/bootloader_main.c | 62 ++ boards/cuav/7-nano/src/can.c | 123 ++++ boards/cuav/7-nano/src/hw_config.h | 128 ++++ boards/cuav/7-nano/src/i2c.cpp | 41 ++ boards/cuav/7-nano/src/init.c | 274 +++++++++ boards/cuav/7-nano/src/led.c | 236 ++++++++ boards/cuav/7-nano/src/mtd.cpp | 102 ++++ boards/cuav/7-nano/src/sdio.c | 177 ++++++ boards/cuav/7-nano/src/spi.cpp | 60 ++ boards/cuav/7-nano/src/timer_config.cpp | 89 +++ boards/cuav/7-nano/src/usb.c | 105 ++++ 34 files changed, 3772 insertions(+) create mode 100644 boards/cuav/7-nano/CMakeLists.txt create mode 100644 boards/cuav/7-nano/bootloader.px4board create mode 100644 boards/cuav/7-nano/cmake/upload.cmake create mode 100644 boards/cuav/7-nano/default.px4board create mode 100755 boards/cuav/7-nano/extras/cuav_7-nano_bootloader.bin create mode 100644 boards/cuav/7-nano/firmware.prototype create mode 100644 boards/cuav/7-nano/init/rc.board_defaults create mode 100644 boards/cuav/7-nano/init/rc.board_sensors create mode 100644 boards/cuav/7-nano/nuttx-config/Kconfig create mode 100644 boards/cuav/7-nano/nuttx-config/bootloader/defconfig create mode 100644 boards/cuav/7-nano/nuttx-config/include/board.h create mode 100644 boards/cuav/7-nano/nuttx-config/include/board_dma_map.h create mode 100644 boards/cuav/7-nano/nuttx-config/nsh/defconfig create mode 100644 boards/cuav/7-nano/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/cuav/7-nano/nuttx-config/scripts/script.ld create mode 100644 boards/cuav/7-nano/pwm_voltage/CMakeLists.txt create mode 100644 boards/cuav/7-nano/pwm_voltage/parameters.c create mode 100644 boards/cuav/7-nano/pwm_voltage/pwm_voltage.cpp create mode 100644 boards/cuav/7-nano/src/CMakeLists.txt create mode 100644 boards/cuav/7-nano/src/board_config.h create mode 100644 boards/cuav/7-nano/src/bootloader_main.c create mode 100644 boards/cuav/7-nano/src/can.c create mode 100644 boards/cuav/7-nano/src/hw_config.h create mode 100644 boards/cuav/7-nano/src/i2c.cpp create mode 100644 boards/cuav/7-nano/src/init.c create mode 100644 boards/cuav/7-nano/src/led.c create mode 100644 boards/cuav/7-nano/src/mtd.cpp create mode 100644 boards/cuav/7-nano/src/sdio.c create mode 100644 boards/cuav/7-nano/src/spi.cpp create mode 100644 boards/cuav/7-nano/src/timer_config.cpp create mode 100644 boards/cuav/7-nano/src/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 326ed6fe231d..1fc7308445b3 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -57,6 +57,7 @@ pipeline { "cuav_can-gps-v1_default", "cuav_nora_default", "cuav_x7pro_default", + "cuav_7-nano_default" "cubepilot_cubeorange_default", "cubepilot_cubeorangeplus_default", "cubepilot_cubeyellow_default", diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 674d6c6764ca..cb7db94b48e6 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -231,6 +231,11 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: cuav_x7pro_default + cuav_7-nano_default: + short: cuav_7-nano + buildType: MinSizeRel + settings: + CONFIG: cuav_7-nano_default cubepilot_cubeorange_test: short: cubepilot_cubeorange buildType: MinSizeRel diff --git a/Makefile b/Makefile index 1cf17524f81d..5ef162fc3a6b 100644 --- a/Makefile +++ b/Makefile @@ -329,6 +329,7 @@ bootloaders_update: \ ark_pi6x_bootloader \ cuav_nora_bootloader \ cuav_x7pro_bootloader \ + cuav_7-nano_bootloader \ cubepilot_cubeorange_bootloader \ cubepilot_cubeorangeplus_bootloader \ hkust_nxt-dual_bootloader \ diff --git a/boards/cuav/7-nano/CMakeLists.txt b/boards/cuav/7-nano/CMakeLists.txt new file mode 100644 index 000000000000..d1215f084ada --- /dev/null +++ b/boards/cuav/7-nano/CMakeLists.txt @@ -0,0 +1,34 @@ +############################################################################ +# +# Copyright (c) 2024 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(pwm_voltage) diff --git a/boards/cuav/7-nano/bootloader.px4board b/boards/cuav/7-nano/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/cuav/7-nano/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/cuav/7-nano/cmake/upload.cmake b/boards/cuav/7-nano/cmake/upload.cmake new file mode 100644 index 000000000000..d37252789378 --- /dev/null +++ b/boards/cuav/7-nano/cmake/upload.cmake @@ -0,0 +1,49 @@ +############################################################################ +# +# Copyright (c) 2024 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. +# +############################################################################ + + +set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.px4) + +add_custom_target(upload_skynode_usb + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) + +add_custom_target(upload_skynode_wifi + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} --wifi + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) diff --git a/boards/cuav/7-nano/default.px4board b/boards/cuav/7-nano/default.px4board new file mode 100644 index 000000000000..f6e4511ae2da --- /dev/null +++ b/boards/cuav/7-nano/default.px4board @@ -0,0 +1,87 @@ +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/ttyS6" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS5" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP581=y +CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y +CONFIG_COMMON_INS=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_PWM_OUT=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_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_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/cuav/7-nano/extras/cuav_7-nano_bootloader.bin b/boards/cuav/7-nano/extras/cuav_7-nano_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..fef50768afb0008f78c84307d2fc8cc15631c00f GIT binary patch literal 46948 zcmeFZdw5jU**CoQVGcQvOb)>00GXK`V8{d+NYDUUhncW*7&HNF9|UZ72-+P(Ap&Yt z8U}(I0WAmn6v4JgY^$Y3CK7AJm?+q%t=eaXLyH7zO4NY_>K+o9o#TAJHIvv@?RUN3 zf8QVPT-Tbt_TFo+!@cfxulu;RW{_+RNA$0<|2O?#82tYS2gv9zeD%FO_x(`w{ujL( z&t!#9WPM-s#%y_3d{AVAGW$huQvGDbkQm=KOOcjFu1lq{H$*u)M3g>!@!^n5uol<5Gv!CRU-k*Dz z1H|U&eZjM&bZH6N?5n91ltj*@=+Sl@?mH`8ii3+A%lCOI<0RU*8kBLM%-%2adnK2< zu+%z#|0-8$dZnv$eHru@}|9p(`1u}GYKCUiB zi@N5zQLfM7jFjVt&fZ!QEAPT}4z5mxWn-oMNRB}cHQ~)Hx5bh!+3}r4(Xmd2W9hf7 zQotH>2K=_-+)@r>a4dE8k)<5%cb{Ve@*7g5sqQq{+}F8aL7!)FniR>Kk)M?&CCO$5 z&lS(&B#A*8N78~mlEl#GeU4d4sNbSEFc$V`O;NhMo4fPIeXlY5nR)jFNFlqd_#HDb z;+lzMMM`!!$b6R5&14y-LElE=i`ivHBp#^`?{j&wjF`w01M>GEEki0t(l=+h88b0a z$T1jIW@!?V0Vz$6b!3(}6$74T;AwPb({`P}pJc}d?&+UQvHTgYPCukU{`(oIO1$wmGg z(gmbWq%cDamvOBr3SYG!!y4H}1drv5UPJx*H?{)n>w66i6mQ47CzNK$Nex_|=iyo} zGb_oH-0-mXEiV!1+fSReq3mHVZ?eBll+rg#yv*Ed0h05D&(-JIpe;?27@<2rW(0f! z?pfSl3fSMSDMB9sL%Oce@>aBLj<&pIv}J7x#b3{cIEk2fcbeyP6J3en(67Jz&fYxQ z=PA)IpB()XIMdBAT}`nrR-)h7Telu1mW9_VDvsWGd~@76VsYF&#H_X^As1^k;-4I+ z*nm}aV26{vc<{#KHCF=60Va>xdm|8i%3NGs@Y(3In~`T1Y|O>jg1`OSv+;Pw6#Vte zXW^@3>t5?7z;r-E2L9%yd`S-|9LllAQ?HTE+nQtViWhBiTuY`nU1D|-rB|IUGy90L zZ!oom2)VLNGKt(#JLdQ02;5TZT?)_D_og<`nh)Lh%X&d^xZYELGmExU1MH#o=cE2a ztD$+;#e+cupOqVXfeT75?nZ?x4s*i|@O`NgF=ck%nX5mSxyW9SSr{LAP85T5J@CC; z{+w}9dE{wtU^DK$T@Cy=m;Ja*3EK^=NsD$xo?QwU+`KhT;{0WO9*px;Kx1W* zCwXc>8_9Wu-aw+Y%dd0O)`2N){NG8Z9w{ElfRqhb7&=MkBsZ;lQi-8CL*_u$mS=Lo z0-+-B09gQfxx+c=pXi=gVqBCal_^;H6=vy$ilxl>(&*?`yPTk}dr>M0uum$9Go?#J z`Cx!p5=%G}QGP!lfc9;6xs*t6mMHG?OpO-SG|OVqNJ{f1svF z-yGx4kZGcO75Uma{H>WQCd%#ox#)`(Y3E_0|I=C~N8haXu{p86^p-Og{W_uuDlzF> zW7lzRT5s&SB&l?r3K-MAkL{84YW$?(laI6?J+kR^{OOOkew>_3G_i@PX_EyjX?v}g zct|sIj3~UyyiHo8_k51jK@={bqPITbarf!V2?~8amXcIvK0!JZWZ3_dpK(RWvgYVI zyqDFigGh&hR@RymI{%6K;@``<_r(3}a-6bQ<>xz)rgnNS8_7W=GjavU6_8BiYLTlY z6OmJqQ%N$-F~~9FXpTdU)6<*|IUPrHiO40kURJVL>@Oq-M7(vZhs?bHd>0+}|CjMu zbLMo=F`~^ZlgiF7>rQd4?#*(Qb*C2I-zzpYW=0ttX0UE} zieb&b1eN~hg>}u8QgJG!Qycp+{slxyQ#B&^7$sdTQyBfs$F-B<=jaFc-Yloq_Z>Bx z7`@+Cv+bOBUlEhf=LY>4%@$f4s}fn?n$=89%&SDn8X(r+w6Xh$Npti*l^-l?r5oW;AUw&eDUMNo432A@%3uYx zUe=>j)!SGPSU>9sPlyS0znD=r;8{#OOXyyB`yxiT{jOaWKDbe9tEq1$W|PP(4-asH z(Q;df@Tgt9&3#+h$t#*Xt7=SDVT6JonUIH4K(;xGgBN6JwCD-{Y`M+*365OWMEnzu`sW4CT1^DMDX>yhRq_@ zh02QtFJlUa){L+sBUrq_=ad(HP{#8#pmRA<+P)ed}cPd4dv-@0ctotY;0j(rC;n1Q<;M~PpsE{CcJq=r7avDCZ<0J+GT^cUf$s( ze()W#8VFz2U`MlgHKoaNa!dM7W_J2Ey5dM1g#q1@Qrw2-boo7RGRhrpq5RxeXTGW5 zWGA+m3q(lS7K>6#TcR8%F&SE!`3IU(wh`M6{}%y9`LCg1V65JIP=7&lqB|aQRD)IW zi{XRbo*f)GYSyOn{aUV<_d7Y?IwhXyI<2CsT9E3iE2R_F#MCGi0Gk+K6Rpec69)6D2)kJJu z0~ZYEWi)Xf%|&7|t-jVoIoE<#BA8ZdKx-kLV{v$wJ?TPfqfcZ9I zo<0b3lLmZ-R@#&I(GzW?CkfG>fFC2Kp@7;vQA~4dv8pD?;n2KrqPKd@eCdogg58z~ zoVTujgYw&3!RfQNB>A{oQhm%Vss0DonB`a($$oHkM}+GpN)jZK>0y(owwmP!*HG@} zi-1MGMtjCz#TufpGP>=}ljJ9lhC_UK%^HgF_K{Cryn}l_8>=@KUu(d-a<34jMs;N} zqQS@P;$GpDACE9E(9$UsU%kvEnqLR3C(11<2VDEi9}e}5Fs4sN+bL+Sk3!huF@f{P z7(An602lk5D9Wk{q z`6ldDQ7oZ*6x}Dsi7~ajIQ{iPJEvriFjk#dN86#)?<@TgHs5U0+LHa#Yx!U?_KtBQ zlGi4i#IF0RW#IuLG_Gb8>tKWyPCeF1uP@8fYf%@Kt0;^h(NP#tiB5Ph#cO=5!KwG3 zYNAqJo;L?F|2>E~#3smr(0B;5H9v zUu)u&zYbAcJ|6hyaX3J`Ii-In(o^eMzrnlBtm?goJ)WltaFfkBob4m*t}24jh3_VU4d^q>xQb}#y0&;1ihc+%^v7T9{PLz z0AItBQrf}qSs-58VHYiE z^-}$+HQ#n@?T%x|JD%*0LmeFW5zT=pB?*VF4%7YOheHPgHO)^Q)rh-H3F1dr_}QFd z8{kEsmzaNF&+U$Xf!!VV0<$~zg^PGcc2CDQd8!5!m+nd00jsDzTGMJ0KLf5j)*k{L ziqrH3vYNFol0C7gkI5%O8tCLlVII6lR9BmtjLqJ{;Pqw10`Z?Da!sg zQ65E!OC9n17vL>X4&kmNQsc>f%28qFo+fS0X+%Hcidv=>F%#cFk*1Y>qQ1QAO>w?V z%v0`S@;+8c`>(|udAl?2f>mw@?Wpaq7cYjU*J*PK#dnyz84o;cd|3{S^ zZ3~pEX2Q%u3DXIgnU~^ls{;8P^qcaKWBeqgfxMU??gEU%q36RIQGdK^N3iLqs?j7U zm7IAamDnmaG9qV6aq+=IwyPdo_tW9f9`KJ-9%Yow{&48egBq-BPU!`&D?Azw{bkS^ zS(T*CfwuD9Gp>Zn$n?~<263OL6G`@Xae-*GYy`~>4>`oA)t#W+*N4Q+yN>6IY<_{L z?b*gK%6+O9^4Yc+VlDKMo|xEIgZh})MgERx)rbtVn64t8>%k5k?mV(d>;YYTtooN$WCU$ijjU#Dovm4I92 z%f7AhS$dJ#%_)b6JR) zwyUzM-q1>=yDpV@J&^A-ZlesoYBOhJ{OvO3si@o)I^F56C&j^j1Wn9aUD zHLTJf=EZjKgL4NplX=h*R_P2|#hO+=m`jd9g8L~(!6}~&FcxSXgRz86q11-*IdPiq zfbR+m{X1h>zP_fYpn03D5%ay3fB^q7Grw{@5e|cQr2Wbmr2k7I5Xk`_pG$aUW2EN4 z;-6K18NM7K%8BDddG~nuDiQcnzQn2K8JN6Z+6Me1p{?&wnItNUSkc?xsKm;hcR2N} z6TsII(?FmAaQaN1(L(!3Wnbt;-?ED3YQp?3DI9uvKm*w!96AU($tvr@SHKH;rjlt? zTXpL|<=TuEtY&=Uc#G2W9MBR<&FQX8skyXvyx7si%BvpGMf9iK6TID}upGBO9Qs}O zlK@9)&ld7E?kl#`AWL3iOX!FJzfY-2IjD)z`yP00V;eDj5aA^;)299al_x13pyM#U z-Yy@dTq)&NzM{*Gcatd@GBclZ#1#|Sp$g?uJ#b@nikHIp(GkiG&jmKH%HRkwfs1Y% zqc8tyjSywe$UoNzvF5{8^i4bs*HCmbygs98uT$fXa*gYh?WCZUYhWVWdz70`xDbz3 zw$dxCsdtX^^Fge2<0`aUlP-$K(^ciJQ`0ff(~ws;B7e6_N5eISN|zR zjKbn8GB5`YL+fYO#6{YV^ALes9fbzPMtrjkb3);VxujfJgsb1I$%*l6*5ouWvy+>0 zJjAkK8;gD=jY5F(qAKKbt9$z0lIg@1QfPJ4|7oNDzek?lv&uaq8nM_*f|4%xVXJ7I zGb^%oUUP>0l8IFoj_~3#`c}hEn|SxMhfSg}pO*OF@GnrpffD(nB^(+u&2aa$4Um>1 zCEoe6gz#kvcAEZQO8hobLTx<;zWQyXlSpHH6cKJ~-YPSc6MFKil4I(Fxh+xXGyAC4 z-252x3I`2iwtOAyXB>354sSSgM18p`)hlc|?BpP4{0=mypfy{*0ogSfvT26w@+K9t z%Fn}{Ee7b13=UR#p)CUIuW{+R;!m4cWqX+Jmev*{#{AZ>-V4t5VM8nB{l@wZx#Nfb zN$y~kTf<|x`F|#Nu*zoO{8-&|J(1ud4PEyO!{wk4_eAn{h6`FCeat?2B?)UJ9BK_; z1GoKFScy;)5;R6i<%X>-Cdjd@GA(Ru!CF!d_g_c32mAY=qt*Z(nV`MnBh-0QKZQm( zH2F=t%bIT|L`GoS?wwA4h^`u&Vy`P`eo|fzYg0NcO}04GBBeD!D_JSO9g*L@&coBU zbT+;pnGNU}I%%DM^9QJ8@(uC}h1NeML()du1%KjtO2+PNw)^dX)8}+x zBu{^RS^K2j7fx^T$Es9Q1`lB_qUo&Hs5|uDA@P3P$W$PmJaLD@0(ywR|4P^;W{V*eF*^UGmKU zo)`W`>Ilq{nHfp`9LPBItNGXgo@^nxK5&w;K_kN|BjCfsp%=pc6Cjpondu|f0$1sp z+~Khh0ejKE*pjCL`h&pz?+xterPel&yl3yr^?)#HH#i1J`qs%Xq9q$DO4- zZSJE5t+a0gfo#wPjho$UXkMz$Ht?wHy&(d*gU%IwN0hr;VB?k<*gh#w`zh)*G{?#8 zrq{iho1S-SPc4^MLCZ^KFO&3AN@oW4B6??#iovzUcSiHeU^y(6Nlws@`@DCr5W;|? zrM3wkRF;!Y1Px2M8$^hUw9x=tMtd)pqPNAK(?a7dm}Y|lBoanQ^K$S@*;N6JrM*9( zMrfMqLfMJDsGmu$`#n|erRubDG6R-T59xD&h9zoWzd>fg9^rZYh6C5bxO!$flvh3N zy##XepTZ3Il5f&1vC|#OK2K_2P1(s_?)FrlNmr&M>fLR>4C=W&G23J^9U$eZrc*z_ zsqq6`?=9W>1Xp(g=UQCWE$TVJDs$7h0e!EjnV` z^*PoR`5JF{)?5e@&eapoomKViv>%K$p*ubS7OZ&M%lHB9&|&DA^3EO9%sT7pj^~)^ z)l!PDOOte#SK|3MNFpSLqlH=}UVBE>=X)Kx0qsqAB5;#kCsqCGsJ4w#N41_c-xuJ_ zD+0uPZ=g&e@pa(oe-dC!KMugBBESl*0Zup`5YWbl5nAq}q_w=9=NLe4?0 zTW3jxb(~tqMnb=QGrUAcQaed!>omxjxaylZ<$ngDJ4HG%I1bXAu_YdOm?3XyAts$N zCrnq`*LR|k0IgA{OlgbSpD7;@f+Uu77qfe&%qwO6%nR5FK|!1&<7jZ)#ZUiA^>+bY${1pJpU7h(JL zK+Gb2v+y76@VqkAFUUq%+F6y3hY=YQX(pdg`y_1frR{>ggqcr04+j0(h<$F^Fi}uG+L`F+xJEF{rjFpa) z%Ez8+lecR}2hW^kl`U%54tU8d?E?HyUP;KStfV#w-K_d*Uc|UHPk3F`hn)!@pQz3e z3HCQuNgBFT&51dMmnv6PFUeR{X#~GZgh5Dk(2JSU#IezYuTqO#+@h)A_?{ZJVrN|X zWj|++_Ok~4)QFTJ$IGRq>)d9vW-i?Bgo5My3Gy^?RsI|3AMqrPMN?8>-MiwEcE`va$((aXa*>q zHZ<3-g+}*y2IhOKbCN$D98wCTaf3r&)EGQN-n){Xa>kM-nxx^-9brM{f@k1Il3Xgt zC)8~w4^}K~g|=a6-SWU03$yOs2VTN=rtc4jri6uc(em0-+Ab|mTNc)R8rkD0{(NMk zcsC9bt0H{1HtO@zxYi^_HM?J5!$h!(jSqxFJ4T}V8Kv2^7OR~~np8T4q&a3kI<4+9 z#KO0ZA*{k^^wMc{8`932hxANO5#t@a8C*Sm!N<%j=!hL9dK1dw3zGq5cA5OrUbW6J zrIeY@b`!S1@9b+|wO8FtVyvuBZ=K_R>2+tHXGx?5TAu7xJ<5 zNL%RBho*W@t1n9Qo#&w~QjQDX*gtJbmnc`Iw7%QxWX(z<<3LYh_?Y-4S4)7Mu5Uvd zt4;)7M^C&rI@jS|@hmwBoEfyFi*@8`I2b)-wje7I`pJ`68UTf(SM+|H>ZkEA2pxdyC!)}O5v(CjjPXl z&!9#!g?aT%q)yEqW^Wg2jiWWrALRSOnJe%X068Oy|HC;4(zZ-=v7EgneTbE&d$Bg*x)_(P<$JF1~!1p zaXqhk30BU9>eNI=gkV+(BfX%AfD*;q-;|?$af@eQ@21?H4mIrw-IU; z-!^h4fO3ZJ$Zq^9mDAQfuQrh3(BKfU&|FePUK3T>UT*DyDhuo$`-%k72pckE?vJz(#ipTwF>ErX8`~%!XlUM} z9<`^6d0qqh)*UuL6UHjv31g;Ar>kHQR}vCmRv))Bz62p<6)k@XYco~+0Phard52ba z)*!^KIt6Sspk3(9!^iM^pEl*}F}2pTTbp>6);J^bG+nEuPwg36HuCf;BvwN!ZQ~0c z#f=0@`l@bd5s0O5?KX82tc^)qJX2DrP7%ESm`^53mcNX;ZSd(lx51?tz}3-bhv9?A zaEGO+ZZNXC3>oehK)ZnfN$JJIp?KJ%cA2Qp@;LZ2o>8BNUh{E0+lT8TxV}jA(BeFV z+$-RPqA*(qn9-G(06pAE^*8o2>cPl6x{gZmj$TRR-OG01T{&@3KUjM+^Vrj{NENOn z(~JFdY-v)YN2WX6`=dQdo{t`#Kn=7P_u@)>@oikAy(mX+mx*HQQjGJ5OJlsye=l7s zSw;GM2KC%^&@s?5KQzGi8vfaI{I2c=m3yUdsC<~dqyE%nsY{uJ@e%=0vopZbO>`8b z9Gv~V{Uh8z$$a>Ar!^jD<7t{xqLX)7`n=ra&e@n{{ z2X-~R9h9hiIJA6#5#U>cRZO9F7`!4~!DDdY-hq#ch9S=aZ#Or`mB_%2IVuri?#dKl zwaA$3{cff`PZpn5W3XzjgT_Gn0k19|)Ftz`L~li+d#<6`DaU6os7;ZxrVC0I_k5e) z9B)pM?zEh!-S2SKa>X2WaDI^ER>*%UH?+PDKlp;?gTV|=Ys)^@(ZpEdvolI~8$ZZi z&u=4B_$du5jfF-x*Fy~WI{Ix&L7P5%xqPDb)ny+$80Aie0q5UXUJtFvd(bUV4e_1U zalV7WVve`5sFk&x4jc^L1HTZ>xw3*2P4Mou=!8E)qD>KhAE14>%22+m{R*4BK-MqP z%O?J2IaQ#W0mChyQJ=o2NgIXT zCZzUW))Ft6OMuqR9~wVcc|Y||*hZ#$rh!g8wf+sNIeH4xdD`8R3V-TkFMt!z({*Ms z6IE?HmF%+o%#<77j%r3%W~TcR7x6t@N_;kOA!(<)(R*KQd(-w>w&yH+zkI4`H(3bF z1GJ1cJnJju@^Yi7v@&_8AYJuiKOdV@dvjrJygAv;Bldt9WM}V|E4+Ja?~=KmGvLxY zn)ag>!NK0}Y$%mqERV=IU*md+1sGIA`6zn?Uk%4xwVBy`=_ob|kPF-gWMdJ9LCvwk z+RUl^U1*Qj4)XVWD!(k&ye&oEMevu+6qdS}($mYL`LCyltC`fY z&+fg2AAjZumwb0|+d{>2|1FL@m#ce=i&4rLm*QCpdgtm|?5cauBPeBDnrp!$Tpc9O z5-w<986jTY>kxpAN~>8E#J^xJNSxk5)ZTEWUhn8^-lZDbQ|>P7UNo`wUK>C0%wf*p zj<#b17Ju1J_fDWuw5{X+))uK_1WjqZgP5W*5}mCihSr}qMC*4y7W>#AYn|Pk#Z^Zo zk`66%HXJ(H77jhvwxEu!`#@XP?Mz6BNNJO@7 zi`0w0GYW*8FhS@tDSB+2OGcu6P)GndzmS}5#t9my=l&$!T)J$cY^lQ zrjd=5FU=IHT^6sDXDn1&XNgw=+>JdOV11pVoAJ3niuc461YgkZZ5gwbA##H5vGi-| z+2gK@0S1s1V%_*WeF#2GkZ;<1$3=7kdccC)RMESD<2KUK0JC9B`l`>7 z4qB|aUIBK$6zN3N3k+qc9S{_*jYl2&W`|-TTDP{;hzOi#08M7zfS)rBg^I#d+h8Di zhhrQ^46xi%uS+drU;g+nrSc=CNZVMsf@Tg_Jx+9aU3DGcI!K)dQsakVp(+Emh;XPQ z+#i@8@qVit=>sGp6y$6DUZ?zk`4pOxb5YGdcokUHm1}RpN^D}3AbiY>UL*ERM%f8& z%mAH84Xx=LYy#Y-^V)>7)aS567kf75ZjC8lF2w4{Rv11HyYBfDfRL^_U2^^qBLAleV_q2VY1Y)4%6`D~+{-D%MRM|dzi+r_a(>~l z!JBof|dSKllkb`#U(?(JijTDb zjzLg7E^an$YmcFEF71Ts+?QO_tao4#JIp%(3_A@sce(ltsuB^LP zt2qN(tT}2^KH6GY_uKS!y-%f(8I_O3UhHZ(?9^SD;LnR_Q!681S3Y8{GrCKeQ_FfX z_cS&2G$!iLk1u5egS^AR0aAYqOcJjJ@}9{NXMuvH6^29K57RGs^g^f;TAtXXv8?LV zr9825_A|W=;|qV=bl5p(%aL=Hb<4Gf&%860?jUvQEOcIYfl z^y;RtDt|kxax0Nvh*Zg{>`GQ;ZcoA5!}kWj#k%#V_9CpTC4642ywAz(8Mr_-6ZBow zTiH^zyhW%>FJ8f?)%~t3zJw?eM!a{iP#1+a@1*b^8!54!_g8PyM#fsb@eJ)3@Q311x|7G?Y~2!O=`sO3giG1wT3SB6l&ia!VS8LDM%jZpcPyjSWkJmy>^9m-e_=WOA zHx{g?ky4(@6vw(qa9wT#0Vd|{o z#8X=4OgMDDjjhubFJY3F(HO?0a$;Iu=T!9U@<%BAY2W@66`T&4=*L52mgI2gY*+=w zWI;csOQId!s;v@7O^)Yq%a_ZViVLhBd)j zPIKeMhjqb|L@1>1rWERfCjIi-%-bx=B6fLA7&3MBW4c=eWf52X(0RmoQM)xUrxvF} z_r)YHm*RvJL=i%xcl#1G^>(3eq|%A2!y;^t#=r8Mu$2`Ac&q$n&_N}n;&AAvgWyNu z*)$7qrZA>s^B@_KPem$Bh7B9=q`rUT#-4|Hah)PERQ5kM#0Mop@0eZT&~JyHSMQkh zzz-=e!0el#NYEABG3$BtF*|*-4OjF6a4PHOmLjGG{E%a*uvO#ZgX1H(d*@(bXJg&- zYG&v2>csYGbrp4&>K1kDrY-2^%+IS6b~(EfEQte8t8q<<16xO0g7JygbBWja*yZYU zrR7edf5t)d|BLJ2N3Zn@i2nW2^bxK-NDJ_uroSRRuNvAj5znkalo;oqpm-9AFYEO& zE>GChp__2_c}SR6aZi-ugX39VPRB#>l8z@F`pL*x`EY1AtX(gw-?c~m5w%K|mbqn? zkG*A_kKA(FPp13*AA$q#pY( zwMluD%Ml7!P|lUBd=#F{kAfG)uD@>RpX(|d`p(d+f$u;1t4Ec9X_En?`5A2BFZyZg z>@5@gWaj3+ve%+*+8a;FxeSgoZd_s#VL&Z7u5lxUsflY3u$G$v&e9j) zE!P7YixOD(!_XHT-<{Q&q``hQ&wVV5d*OtN(wYe|rwaqi{yqWo0z$=dGh zoA8+>>jJ%~fqkvzbMvM$)H!@a!TrFIWw45E z?z?$}!MJ;m{Q7gtrp0*sk0Z3bo+Hur0!PO1_mh5N-Q3r8#IoIp5$fF>D06C?tB>6P zdWKfcejcSuusS&gm2fzOL_IKflf!3IFw5sl505s zSSe$E?5-5qDn=>QP{=rZSvGlD_+!R;r;EFa%$nG<50(5OLcKDoX#5#5|Dbp%#1CK6 zt~^`qo+N8vv3xVAP5kx+O`nnywS;cm619Z>5LeI4V*mTSvE#{%Lf?1YnNzic`deQR z|DxtUL|`K=-SXe+?JvCrs5=zLmcOX>hn~O;DVza)EZE|hVH0)1N#vC_hmbW;KS=i8 z3!FSUNDf?14~PCR_}`!;tmQ$_;-`>%V$-kG?;eeEIkXNFylM(i{>X5qzzyp6?L!$# zw;OQ%mOIl)l!aTup=t1XhNMP z4s`@R(UG&!{-y>}Av=IicEk=HRVj_8`!C&lDUBYZ-zK~#1`naMo6_(yMT&z)SpN^* zhO<9F^ki}R58N2_?hJW?44+LkriLBRU!UzHd#IMg!(}-pf>JYkZ}*V{@a-SUG*9j3 zwBK`2mKdQFx~%WInZfv3MsfKjX%<~cWqwvs*z%kNK%i>izubG($4tq9h!*#nfu-){ zkg0UZ%QvQNYS1R1{X|{#?z-NEN&7clfR8k*Bqm^Gvxt2mj_w4*hj^B@asS47fSo?l z+90&D&SKIN2kJL(zz}&>0QrMC;BFxY<`>hx6}aj9$=HLZ4|pOaexRpb!g0aOxO)Gl z&(R9Y=A1!)(gyqix_kX}AnjI3hn5ZexPLq%vSK@OHuuym z?PdjyuX+=uYPyu_jV+&7Z(=QKppoBvLvzG{8V=p;V}-sj^qe}5N)GR-eFdjf^)^Z` z-ouqrts3l;?MqXnp3f-1Za|{@b3`|Q`5v3|g66nIoswDPKu7i!X&}cDp$odzg4Ty2 zbC&iq@V5zv_NjF5?*;Eh>!<-QMtMZf)G==q>g7tMW$a~xQT{jKF8FH7)5R626=mU7 zAC;@eN6t2eF2PEx&*jslSqfCYskg{|8BJhe6}WIZfg5srQ_&hyv>&9*Y~Bm7^B z{CAH$R|Xh`pF`wk-+F30{uXRI*N1kLup%dd&x2=#Bi^Y>8I0(ZMlA1bWFID$gh4hn zGw*w=)9&YkwHojdjzY*5YiiCkF|+H{m5$ZQW?q+5uNFJj)UNAg@TO5MZSV3EA#<8z z%K4^tHM^o+wI^lTJ*vsz&oNz{Z8p@datyD_Z47;pqhD)OOQzRNT^XQ19Uu6rqp<& zy)s>HynbPWrLTR-3H8FX(@0LlFVH;fT{!)Ly|IT~E|ttap>~?+|EH1v%aQ-9k$)xf z-v_VB#o>`qWq59c_YIpfB_+?LUR~r;KSa8mn_ucuKV4*$O?kw63|27EL6b{0#k*7k z-WxObIu(B|PCW>lY$chrRBohHA<0H5lrZF?RQwK<$}X8w91FfWJUbg28detE7G<;3 z(uYOdx5;Ty!fc9bi-nUWyW@-LNgU%)Y9#de2;v|6AEv%6j=|8g@b94KqQw11PvVhc zkHnByp!26Vw-eVpoZtpPtK*Tr)b&u>O;bV?Cp&?gbiH>XQMym*KaWJ|zo8(WK;tQL z#Wadwi3(koM9(-miMsVEB%5_JhzTId|GWtu%)i`cwEX-1L! z@~_kMQ|P%l%v1{~Xk*Zz^JOrFhJuqY7+`F0p`y%$0Olh_@JMPs4a zifb7T9e=Z?DC$Fl2pl;cZI4%-nHpGCG(Bu`eU;!%lastAd5cqX`g!RjVjwv01^6?h ziw6)dc=U!RQFn@qfwtX7&cS!rzCzz0NQSO3sv~(7bn%zrebgtg{_8gGv#P_~(PWX{ zR~-we7QLqR9>{es1J;y>D@6VtK=@C_a{2eVlrtYJJ9UNCrW78P^xnV7zn79_yp1;$ z7UF+7&JAK%*0o$p7ik?Iq%V`(b%ryiuds$KQjGVU{0C?$X?cC2QCciB3d1n2#ZnsL zTf(6&fH94-4u>|jsqj%sq`Ss9^p{wC=xGP&l*3H>OLFHyM!40d3r^HbQ4%$;Iqm1D zN7IaOGvJbUiq^e0tOYE$Rq?M|F7DmovflTouoHxSk4u^h5 zZO&f!u>xb#Xv7Jk+UU6mgP<#VZ>k-ur+6q3kF^5rmJ|mM6g~V8Yl_^mQ5p!u!NZVi zDTaSyO%W&Rq3J;Mwzm{f91J*%&)aZ9lVrp@cr}VUydG~oVoB5GSc#U10VQ|ioy|)< zZudF|{6vWZesPEbr{A$HPWYYSv?H;mC>A!cC0=)=X7Fw7__j2;SYjkrioU0PbIUF% z7O~^e{u!k~*l=9vF;0VOp?;AyMbwY7rpN~$%GoV(QeI1`L z1d&D5n%@1{M167BAiGdkYBHitZeb6@@XB*xyA;*ol0WUAf2T8%IFNMU9hlu@4^bu$ z;1mbL!J@&?lkl8vxyf*A80n2^axrt34F3dd-ObhDNrD z`fNtOp|RV&qwyc%kUjj*_>ZjVKZkDuwHa`7oNIp@hu%fM`PVl){_PEg7KLio^q;nI zvVd=a;m}*q-cc^d4(o6`PQfruB2y8+h#Vg*Cq$VP$-Ri2Q9YwxE}sIeB~e~SRDVrt zvs!3BpwpdY!1)kGuin~i(puZJ;tWKxXrZB1n_ZwoIDf$Qt&XFSvh(0C`--}zYRLPK zs$))Fgp#$XSF5V3R;N>}wLSQvbE^N=jM<`Dl(7cy1BDuQ{>Q2aeFMuqiEB7?c!ZZ% zJEJj>p9c8CThkN0QCRx< zC)LbZgNP>u{XI|p8z~()JoE{4a5R2@D1>u*tOFeeQ0pNY8)rtp@)(QW&TMgE%_Axx z!qMm*;ZXKF`c^uB3}SXPVi)w#$Nh2BPNwFcZ1jpg_UPE-)KLNA!(@);B+ zkrU_on0YwcC4aR;q{-$f_+O z*Tcu_a#GG+(yvo=I^7`ayxqa&2!-3)_<6Jhlf!--{hsxv)hMmM>0x#HdH-{TJkS;3 za{h8o2{1W-IG0w#bdsDwoFw6#OwY4{ZvIYU>&HDE&mM1VVH~_=n7qA++aZEb!-+AS zDJm0>GmGMgHRxZK&J-AMVg{bsXg$!fi0LSwR7<80_zmebMQkB6mlF-md!0HTS}4Of z-2_qkdvSh+p_ShC2NJ+V*_%&aA@}SAZF|3>9@2_uDc#l6TwAaz?X9mmS^v8gW-%CG zX6y5^axUWzJmKOife*o-v{%&>L4Ud+c9BJPw#42Qdv_ePrMaGF^qLU_iN;F6hhqM5 z=Z({@g}tZt6~V>_x_st!qNj;~Ns3&})QWWkUg)p9L%E>15$aKjGZWsVG{}H;uWv5( zy5;Tgc+zkwt{qZ}S6?+0`q2=H`27;0tgmA|Tf*Y3n>6r2z9U3`5()9oq5%ItW_L$5 zPUCrjSVKN~zoMFI_zVssdasr(+{uea`={C)#2HPy!TWpSm^p`?=ir0UxHAK`ml$8= z&KXUI9;EaQHWknP+rS6?s0A`}B(`ol# zCip+C1$`0^peKAVoeYMSjRD%uOY#-Q;I=X5rTgWZ%A_AWye}ZO%#&c}e zeu4j3@*d5TwgA;R)yq0q6PZ1y)zpKr!Q7Z)aWFJH>IT}5xHw;0}1?WUNfu}_31S{VWh3K8o$wqUV`Ixon4fI!=&2>Px&B+=djcJm_BNbSVy9z#`m0uJ+hgIT>K5BtE4U9}5vU{e zEOB54Vle}Bwb6G6BJXT#x$`TaE!393uAj71@A+cwe=zh<$5WGFLhrJY9Q#u*tCFqH7 z`ZYmQY&m+gafqLsjyXikJ+tHWa@6V?xDvqpLD%xt8PxS?^+gM{qdpJ$*e$6ik*#VX zcA;~K#~C+W<4@OV&d?q8;P90|?DT$rijtkk`Nl=`GygptYgPj1pr!GObgs854*h}Z zKlFNx`-&(Rbi@S1b1$RjzDUiCKi2$3z$r%Se-tHd zp7$6r%Z z;_ITY(h%EBP*%WH)3_}fU1xHW8CmiR;;i#@ZVvWG&N_HnfafK%>+4jM!v2jxVJ+eY zM`On}1(j8SzXbK_U>q2HxXL}zvSr3 z#BNm8+w#VZXE%>K|Hh5&o7=Cy?fK=6?He>Ua{YInPcGvugaggZhko=teU9rf zc|UXBjjImV*oY_dk2?1i8G>nv7ktD@l%IQ^?gXZ9`8uXsp6hxxiaW6vx}LQ>mx2A` zK>D8|r}EgqTU2*ip6f)3WBs%3q$xRFp)2Ma>N&Kta&$hq3za($VMjh6IJ8s3Gf)eB z`S<_u-9Pa_d%kh!Dtt%VXXdvCR_#3a<=4sSef0Zp&}z$dwhh6ciowYD!YXAtLmMSC9Q zpNTo$PT*rr@j4T-(qcrxQ4A-_qDU?mxgy8`lL-Sq7j&#D|57vvZ^*5|@UoF4HrU)QtDZ9i2xLq^l8>b55TJ+>xh zPS=xk-9)+6GXaXB@TT!G7CbdjJSEoCzKIwGY+J)`Vqehu7KjI-McfgAp9UuZQEtJx zvwn1KW&5`5bnc94s(+Ajd0TfTp63R(_SRRrc5WSAIoxU@oTzlI=GLxwu-a=Z!u#u6 zE4S`UY69Y=xccPSo8K}SBG}zb6 z52gqiP4(Cx+pi?$ajVn3)RQzEI?zh5l-uWN93H$d4#*KZCb)b8uhob&fG7^CwZR#; z&=gVsx8cy8Ektp)sLk~_aV$aH;S^4NK*Bc5xo3z2V{Q-YMA`d`S`ReO@^Fzlh19e# zcQn@i)TudNfOzz~hY`_4Vmto}Z$?5z!;sMCG&=*Qzc2l=hL}`%icUoII;Hv}p>@!o zA+D;HxkGnKl1D;zcn4EV84TU~=4+&8YNdScUVEY8TLkeH6M}}sn|}IaB$PS)8F)Xn zjGngCAWjq~iQxQ|q~R@CDcf)s(ziOOU3Ibeg38+8Y>N%*m_HhJICqFK7noVan8n@D zq;Tgc|1*BX+Ib$aoU!n;{aEGOsW0xbww2D6s?Ai^y#pRceDYq|#GGz{oyEiVd_YT? zmM-H8zb7GQUxD1uzRVSi7bQsY(NX;9wAc|~@(r`~xflI$K_-^=hGZ{Yc>O|LkY#8; z?m|C~chGvuy8py4Rdeho&Hie8CmcF4 zs@oa~y*K<%-4@P7d6W8F66Mw5L^m%kmnVt4pwpO)Q4EBBg5K%QkAz+wCNgh@M#I{R z6A%la(O4tdws4*4&p^*SJADhaz45?zDhoe399zsi!{C%Y=)ktnUBm@wl#l8)XiV!? z=ry=4)Mh}x!TB3F`@P^SRkH;j{I1-7!qh4uidBjj)Z;;X+8d|PWM-$;&YV8rqgq3?nZsU{UOO{K@0(VdYM)j@l&d4v;Q1H$Y|<3BRnC;T z+L^XH{AB8F;-VG{{G%8yrvfJh@b6z?A29;+_~1mwMRhg*3!TeMYB5jr$9iYxOoZ0> z-7r^s+}rgGwf%FpR9~Y!RV3MQoff=jea|n{oWAri$)94{Oz&zr-g~f!2ObgSuh7?_Z+Yljo(Y=Fe4O-Z zIL6B_>-1;qoo*$vA#v*zSXq2u}jPJ)ea`Dg`-0S6D4Tok!7sq!n`(bz9 zhX~imsd1EZ8HnI`_m?W>bnj~MfODDmV$k=?7_4) z24z-B(?oFcL3xhzPYUAp+Ijwl-oQ6%i8sF&Ij+yN_sQU}D5$7nq=AxgU3Qh8w%+m|7 zF7E(3UcDnP7=5$L;+^_@qRRF!iF2I{!ZETKH4w>=W!(eUt>YU-tab*$B z!1{yK(5e2npe?l*w9dN6xr{oDsDOe<(mLq%>wqp7X8DJoQ0CN@cJv|V<1MHBYWONk zt6!7)SFbkpYoE??%)dFFVRt-?BJFDW(D~I_c5}y2y(4|8WpS%^c?iuFG$n;j@CM|h z@m&MQ*L8TOBKz^*=tq(XI3QmDC+w>Pt6foT4&pO$3Ok4W!xT$q5e}(@V9X@ zFZf@!A8dKsIZAAmg@wVu;{Fkym-7uigj}EC&S=kG%(T7emsS02+DR{s*7<|@5@g*A zG#qY%dk$>3Z zbc`tc_$;pp28?JsQMmM2rwU~iW;#~`%x}kT=QfObZtx7o=qWf4D7al}abJ%Kl-=;tu@9>rt^+kAd|qE*)&OvtOoZ2>1!`npVEO=W zF?m!82@fPVqaV2Fw>%KSkS1IS$hHF^U|F-usY>9IVjlns{Jg=yXTSu4gdq@NSkfg$ zuU=}3o(GBU1^gt{R9BM@PO=J1Vkd%LeHjl5Y~&u6XR^?bxXD|aMnTTS1>2A^C$Ul zx)z!=K$++ZeAM3;D1eMJ?RI_w4sm)CbS@P{_1?fWy}y1IPOXkrhkca_eCx=sLucLI zz)WaQV{esq@iaGwc64jx#Kv>}H1`ERG{+`jb!nTJGPboh5Do2Fb%IGOgVrZo_>|09 zpOSfCp!Wv00^x_^X+)3?*)8fGWrezo84<`eC>U0=y>{nB=+w>}MtlD^6w7bq6*W%r zaw8~F?!mxwJ%n9BJImk8#?A^M+?O&2%3jO*hK#`wkE$(J0;v_>k209ly5VwPjJh>F|h>x&b~nSdoJkbUQJl3 zShGd|_g29${}pUx9rSVf0(o+_4P1l(R|ABV-MyeIbD;h71~PinJ-mo-$XtwQU`c5= z^ad965+&U_^rkYMyH*etHq%QdB4(aYh&_sc_uPIY<{P=&r&L?W=!#(&;nfn5N@25~_&sO<1BeP6Q*|j1H5*LGk&2qH|_Z%$!WA9@5Hq@XL zH8|qeqUZVoNBimBhbvqnmG--~Cb#DYzZU*n)bcxwuNa&O7GRIM2Cfe7 z1RT+&BE|d(qh-!u^sI|JML7B30GIb%^7BO`;Y3nQ`~i|-qLXkX_Kyb9+)UU4a`8Z5 z-+NJz)>%9l)6Ne`o9wZ(uKn(p!3`b=bPwDj3vb<&uWwZ!gWi-_i21Txo&$d%5U%W? zt5n+})-VI>J?pTLdShi1YT^*B-a!zt$11 zx$f9*`whp^W3d;X;_&*;^0_-4de7&e!`0Yd@8GrKi3n$X?2UO5jtqz3gmyG@ISPSM zriLUir;5$}9OvtSz?TEsPC*U)+-h|^(fi%-dF!R}#5(!;PH7}$Gp zMvnuMa4j$WvrkpG&7bpRtLf>6QCI=A zqI$Oqk}uD~=0*yxNjgLa1Rf*y{{w;RvBo<*z&@%I5Oddnst#BJxY9x+G7@`9oWZTV zeq9q}XA;O}1=)uQt)$o$6+c7Nh@{i9qoEf1K}6Mov|H7|&LjhH)iZ%u;=BRxmYZ<` zd!V#$Yh`X{T|C9|&p|k2a(KeE;sNnM=UhWk>%q=c!!_Pf@J)u<-h-VM!?hS2R#jVL zSZZ-=4EUo_EqtGDW})O3_&)7by7q&e>4p@fv>ML&3Spauug6(+FJDWw_{z7ZGar)a z6|LdmTNQS*CB$*2QiK-m{+} zIrseoe*kLV8!c4d3F2?;g;KTfHquQsv?}Rr(z?xfcEv8-yT=fLdkh?4)YSP)$*f{4 zVx3B?d(Chxs|Y>U?R*5WE(70^j5>twv5HOpJ)JAj^6C=@J4^94-mVOnzELeowMng& zC&ZVEmdfhA)I&l`ok;avD2@W&65jH3CVknj6L)-ju=7sC#_s#y2^UeDLW4P?Qx|4P z5q76Yy0GLHgSq)U9|2p7eJ_&TA1RFIrr5nP5^u2kVxZ3hq!)=ncgz$XE$Iz;=q+X# z)uOhjEc>uSj*$ez>m4es;F}3KZ4=gW(1GXn_-5p>Nt9CU9Ud{;3aESmZ*E;N^dAlD zieg$Oim!F(!oxds8sZ?9HO~}DQ{&T3Gx9zc`TD~@6ieyhN5OkY4L{;1Ixy!o&HA(v z&%sl^_aALMEt?v++L9u!F6Nxd5DU7A@TNL5B9GfX&V#Wt&YF_qjq6k!Qrl|tQ%)X2 z3Dg5TcFOhni6=oL)N%FS#2I?4FT(Oi?H^iF&vmTRSh!58Im38=!}DN#blyJu{+7$J zY*LIAW{C4;ilf@O?S&KGZ{(i+4A$iCnDBQ$n|#V20~?mWfXVdxsTb6>H3jN=Zgv9B zg_qGA6U2Y-4eB|)uTfODhj#|AwkkbmaZ)Nuf3rx|HEuacHL4R;wUK+5Hap)X;?D4K3ba025BbG)YDDq!`PAXjm)GdNe{ z+Z#{$)mQ^?#(A;XKizWHAKw5P8(a(=I}!|{L{RXjr%Y&}w`~EI%v0ne2b*SbUUQnC z0iI?!m9wqjmVC%;pTs=5gWl+~i!-9r%ArOxwiSH)16N0NzA=AGOXMD_`Nq6(P=KpjqU7j!S}C>_{7HF3oR6FF zk)NK=Bi9jss@dn~rtj?xkNC9F>pvlKlSg2E!JL}?6!6#S9gX%ih?;hxGnkF1D)lbN z4;+6F-&UOpNGA!g;!(VZY;gQX=S|4NSQb9W=X}@XZTo?08H;g^womQ$a@TfYcCRo9 z-KJ6=v#8AQfN$R=)0z^{s&!#B7khr>IhKsoVp%y#OqGlgTHuNoAzadt!%ggcqAw2f zTkW0Lyb#ERz$ka4u0puQjx~H%&(01(z`jqWG+)SSH97-WTXX-6?ETqmf z-hFm=*GKL^?8U}{yj>ld2q1>`ZEHV)wTEq_ev1J%|M%r}v?i{3!Hc_V^er)sOB&xF zTjQtp#{NrtlO=7$!OkTHYMqGh!y47e#;_^#TEkKcpqHnT7ETiJ8!L)4sr-mebyyp; zb2u+Ef9t0wfI_M~!QFVIvD=?4jfn_{{#K}`RNk@FQ~Xpf_0uXpUmsU-b85JchxJIl zHrE;J)IG=H9R&jw{U4txLVw4hFE}rHyvS%d9U3nP9f2N!dfnH4dY?&V8aJUeZCk^sGKN_)`OxqKeg=*?8^@1e*$`$CXZIa6dzZgnm1ltd8R;| zjc2kuG@ZQ0;vCho#9X0_((mZWs#vUxr@gUQ%{85z5}#@|nNju~F)iulbEpqJjnAItLvutrjL1STC!AHaOp1Z9e{Y;Xv=0VW*9M(f4a!!0 ziv@^anB8IV;_0#3ppztssX!wd>$<^;nwmw<<~eu@?78xMEujge<&aSw>k#>4zV9AIW%9hUR8g? zg@TCJI`kTDwlHfSR>%%th9~LVnRQ%dY~J(G<{Ber0RQM?RqapgA?pQQ#7jS={#?Gg zt?`2TA#R2n_jR2b0hU3a{r76a4d;y!y!6{1v{3c9$ZFc+IH2U_!Yaixr*9OOiEP_E z^eJeUomTx)$cwS(wu|9F^A%+7b6zU!*(5#zn#Jg$x})B!Oc%6h>7Q0nOVw?mdW#V& z^M-4E-nR>9qIX~~GN}CixskD~NtagXbD6t+=7ys=xf0g)WVqdM%>D7JzkN!@tWA$& zrw9o?QMH@HUX-j#3(D7WHh9b zaldGmjxQOQR^~11L2RGxtm;lQrnMbh~R~12CUP(tG)-oD#6c0*D0cU1q z1A$e|ME@Qkn#+hPoC|7+3Ni~E~tU5brqUsN``na;T`@P!?q z`TcmZ%WtGN*h4&<>+$RnCn=>B_g?K`X{{%p$FoT?{89Km|6k8)7pBLW(mCJ6Y4NRx z?VyIXTmw4y8y%W38E3PWo*>2ei?k zH3n;Shu;o5c}V)6$2&sFicBz{0*Mdl-b0+?e{qP;l}vg@p%H>M1zdU1v#wK%Q!1jQ z0YjMY1IYOkb|dQ97GA`I@2PH2g}h40!f*EBUAkVx_aXjr8#JyGF8IfTPLUWx{8V9q z!@)}@pm+E+YOik7K<|?fu#JaHu{Z7X_4<>M&V=*=_`?3+&Q6nRiG4{9Nw$YA&|nQt zsNkniearhuMn>Z!3rR%bVp8iN;`P$Aj7?DsEGTz^muz2aX4l!roiG4hOV!Crfrbs4 z$dSi@DK7()8#Sp8^3tDiU4vBvc7#BeA?^j@z~_aII^zX3To!22`uWUagvowBuyXrI0>9>pHT^vdmdnS8G z9~%hyQrRYEBHO~+8ZCC|UC`nJwq=jD-aLC^>W{75E2yW$TE=Z+!Zf(io0(8r`HP!5 z6#g3iGgY8J!OeJt3C(b~z&!?Md6Wqkk@w1c|1Z}sATN(Pj>bC&>ggs;Jy9_o<^RWET6(t+_PCR%?61M0g>|7yO+8sLQsLBk zx{|ZtL>a-G9!GD&CI@VyUJMfQy9W4ArbEho#!FAj;FMT**%Mkd;9e5y4$|8+wRk5s z4m-KHW*g3ZaTU?7oUSMpZw8HH^4r+62LrnXC;3@Yi+>4bCC+#eob>nLUofvZ2_mjm zo3y4`MIgpSxo*7a!RH}cMgrQ#m@DBmZ@ zaj(*zhbj}B6BPZ=39$d31l*^jytnM5ebi5asz{O61V_>w1Wg!YWE)F9(p6Ha-KN^k z*KydBa2bE~V;_r?5-05hzl4)^1wm&>t+CrA6KdD$r@ou1JS)GFB~24^+F>gk^MS@S za3+OpT+e}{Ii5I{CDI(EG0xIw`O4#GdWGlf=HK9azj><|Aqpl?`XZMJ?_mYic{fY< z=5FrJR&DN9GL-Yf6|iZ*0QS<8x9)e)%^%9K zSjoZGW&f}Ob(n@6i`qVFoRGe-mFjd2!bRTVZZD*Lw-0WHH0?25Z5>Q5s?VS6OD@`G zpW}l~?gmPce=Z_oDcZMjFqFP>a7q5$?(*MbK19=e2+fB0ftSvN=DcA*@~n#=;iLH? z?B>m(c>Ms?qikTLvZtqc8mEc_PkTC$>N)8KAj)#EFZ8JWd+#xvD55fdDfyqko6*#| z&Lm>&Wn)YZ+c0OaVNUj44GUPZ0K|L9mG+I8XL4}TbG@(`<%v;rnj@~uHODxoI0geX z_=;-Uk{u=|X?FDo&Hz!46;1Em-MU3*C(^r^wSz$#cM~oBbPCZ-#?I%spZ964%$rnIl&;dn@%AjY^^M+~t z1A)K4NB1WbK^jVFMRfzDQv2fOY0=|TvAfOQ7X!{BY+8cAQgIoYH=d0++w^BNhHLyb5dZi%O9ca7#37;X+Swj6TB-RJu@17 z=6Ozc1@=#a-};MS#fNw+HQM<|6;1-t=Mr9AJzqVDdLnVnk1lwf8-{8>knY}+~i1Z&V+7m8sv~j zN|z)A+|C-58ttLoSwk~QG`rCodm)ecKUui(%3B@#v7ayPE!+pJVC%~X{A6x+6|Qo? zVUBf~5?(65)x{F(Tqj+z<+qlfEC(jG>(;ds*M?h!607*Ro3lieXQEZx3J_x@+pH?! zIaOMTUr17d5e$}{6g>{54v+mOHu^ zU{e=(*Fvv0^KqlI5f*7;@*rJn+S8#5heU2BQGV)SJ#9DWRtZl(1?loyd#cX@Irmyv zd?Gnq4jg1|79NG_wWlZC8r`|tp!Yt}tg1x2x&FXP>?MPNa?! zyNOCP#oH>Y9agfJu|-9;b{+|7oIL`KGiKf|CmeaE@s%eHy-)T>HExBC%o1oQgf!*U zz63>{{5i;plO%RO-Zs%uNyqOSSQdE^I|0&N(r{zX=t z^FkJlH<_IsC6Qbsj=hu#@D?-#crcHP^XLf>dJ9j zIiP`Lr%8NO-h?rE2y!`97@Z^!$dX{~11NKwFdM3@4}q&+X$3+LX3Q`1WjWGo(8kSH zaNCpGNkher73|+ECYqsP69(<9?REhgHfF3mVU5dT-)|(F6|4N_r_Uf3YltMzep?HHwfIJywI0p!mh%`NDl;PV19VYsUsKvd&?03r#;|**XBqVy3 za~ZxfghfAmwF6gl+Fb_ZY0_=di;vL!{FM=oJp$(4or-??mqBK^+_o(6FF7DGG}QwdTBNKV=%+i1N3jy!8qNM3ON|62ZNscR>G<`rg)rASR_NK z9|C`W5+um2I;@C@t~5MKZMpfa14uW6g|4U~(iU2gH^ zyNaAP^9~2qJF*|OhTY!ZdT|C!I0{MGRE+9Y;{>P5k|Vjfh61#ck^F9yItBWCz$^@| zY_D=~2~>}*@+qX`e@?j#C7tzF0sA5p+pfe?89-i0KIK(kdh~wvrT>1A*4ZkDN3@wk z{quRB%fXW8cwd)=25pJ{s+(mYZG6$q`Nv^-Pu+Q53tjAR2hviznvgbopSEPo{B^(; zLC-yb)fjr$w4RdQHLYf(ccdAlwGlj(i(Ce+jkLxJS6!cf5~xVGL5`ZknAllB(p5w` zCz-vc{r+kuoZbRD!jnuO4Dr#>Fo}iq7qc)ar`O_~g6lZ&F18gA)sXfT7jr_Rm9$ON zK87=VNTUWiEQ4(7WoYmg0>Me$`Jsx&@JR3sgMni~4YacnHt}Yzek*z_)UuCpKOOhC zVMV9=8L+27qvs&*n{j`~(CGR`E_Cm3(D-^E(w3Bl_H~36=4z&|wEikC^F2F#sn7d3 z@FZYW0kg>8-+=Wp7$_cmOPPyrVqZ*cB?_lOd=45UH*9!*!-8{Mns0*_IBCzxsv7Ye zH>sv#WQFZq*wj{e=faVaLv84NdT^s}5jgEncWY;pzTg*%zM$&!+^bhEXzt_xDnduMy z%9K(i2TQ%ou%&fa;BdUuOEsR;8V^WUfx6+-6rP5|8Lkz zXksaQV92B-CJ--31Ik2S0H3P3a&h@{l{3mhss{E)`zf}_saiB+;RpTeJ(brLm{6T1`$Bz>?+xbqOAJt}KDhqEdbscFm zxwP#ni`rD=3bP2VCtRPnT!+K1`-ea5y6@oH{TFTn2UX_cfy;f*H#9F9_P#BD#j_$C zneb=$J~&qBDmV+DO9pk=%O_9tIuGeAn#2g#0@saYh2_hojr%l}-ddv-t&`F7t zF;WBp^Q1HAws2-Xp;!uw-06ZOV^pu@_40OCv1HW0zE)#`6^-`gu7vWEa?9E(IjnsZ zDEgz16iZtD_pl$nbNvtZRmrgk>-6pSSIHCHmUSiTURn3uI`jI{^?u+gzkJ{1`Z;@DY?G_x$?a8gqN_?y zcC1FODb`5jN=04LkRruVC8s0xRJdty)+1H&banydWg?CFo6UBY zIdD3zl4rqPZK{%IBgGt~xW;%b_MB2BY2~Ov6&x*I>$$3ID%=E51JE&_g{HJ=@m~P9wYSbA*Bv#5@rRg zyCeMW&r<5u4PFnd0$R8lZnt)8NC%A1gVso1f8e@-opxOt^e^nCz`a@ozT$__P$GS= zzQBv%QV5_Usq1PT;EADytwE=!p+|4a@_g{PT{7|?R1zM$5&Xgmr0qpdaV!A2(KyJy zXF>8kBwwuG9}WwCk2jPRjsOeqi=hDBuZT0 zgY;R{j`V5AeJkv2>M3J?&RR7mcO#`SjvHmA$&&S<`H(utK<} zwBpWq73AfXq>lITqS3q)&xw~0c=#-%Db0a>dvchMQp!jfN_Wx6XLb5FPl!pqaDwP& z=b?jr)}I9``VT;z2tPF~dBW*w(<|+9Z95^&2+og(tVblKM4zH?Sn9PQ}0i8gUgh&Z&@DvZ78mfnq89CZR^b^W1#!Ux1fr13i-V z^(0-P7LCoHc}6+k^(29M1u5mYH$67={b=O7>`SSbhH_>pcl30}3yn3`G*RoBsqlQI zNl%#`?>HbeJ?13sR%j+T*|bI8 z*=0wYZCxWWU$l=n)dVf2$hOxm<=hvR9*!@QMw$|){Kh0qvUM32y=V_vp3}82gP!B} z-VE$s347r0UPb5Cd6g#vHaQ7D6dEJ2mSMqF52RE;i!Z$d-vYnWKdi@f!aE(>U`)!A zzwysTc|I?d`WG*^$JV94fp*3$`B>XwXtrg#|AN^ou+ROG`yXi1z0JJ|1gKT)cfbOJ zUYWLyq_;Wf8j?n{1{BY}KmsT%G)hDI4lWx>>JtB!+Wo1=*etln76QYmN7^O5W)-HGlUw;R36s;KVSG?&@UH92?CrN?Q8x?W8qLk8kyw-jWHaG0@+H-fOZL z>&hk!tklc?hnm+mvy}JnCU82*!LGA~CC7t4%5rGzGO4Zk?M^{|?^*Rf&_1p)~z4TMWs+{v zdm%e*d%6a}Q~7$nt&6YZv*+a5 z&S`D0c0{V#r174wY>M7%?sS~pq{sN?;NPiEY|294=W(dT^?1I_P1@Ht*l*TH_Qhwy z?m&*vr@#1wU3X$bj2`vij}dS3th-A5G@$u;ee;AqChyGG4b_1^wlkk~ zodEZXWG8Ir^tKlN6KD-fXOaijAfOA0(`Kk1`+7HDW>e?;p0M-BH=*y-2&@H9z`IW$IO3egP;5yhOD%n;h9UhU$TS6VPw!UcP&%@8-Cr zr`*(cTil_(t3=-^^;X))`h=nOq3`CbL;K24@Y%ESK95Dui532jJ5733ueLj(SAQ`+ z*VL;IaJ|}##pgy{Z|>E1PRyN6HRzexTZI~oqZ;Id^$ERO^7&qE7eh+nL`e(~gRF(e zw&aT^-t6SV%y}<&gmW!F_g=v{t^l==51{w_^aiI-J$4{J4Yinzw-;uES1xG4}Xa@9my_9g+N99h^?rtMBi!Er3L2z=nRB%qE5UbSfkyB7nkp_J*PR3Po7B*{0Ln))qD$(sfiEfhKKNSB2Fl_Z?PX>CzWKZTs*nSCv4%SFq z3-c1B-8Uw58-Wq3olkcXy4|>@x-vZ52*+5EOH=BB`Z}2$g-?L3-*x`a&`G zD`MsxWYXn>9I%6_Ea4~CZU8q27DlZKe`i8uDtKRFSgRQ{FQT0>X)SUr1K$ZK2ZvcF zo^%OmrDKOS>omS!!r|{yesU;V(aU2-cAKRralX_Phh6a4>Z2DU*v-y3{pbe|*i*eP zJbu8g@o^@7lBSO(-0U3vU``iUc0f6?cX9A1z^8D$H%AEzEw?5upAaFgpAZhIrm@F> zOR#21{BN7n5;xi7UEGOn@wdBdvC?5?`r5xV>8yWAlHY%G(iwb-natgD1`8%hMMst>efeYOL@t@fiAn86*vuEofztiJrX$XDd4DD5TXe}~MOE(g8`B|pn~ z8CdF5igws@d}tl+w#t*Sm&kHl4jh-03W4d_rx6q3U)5&;XFJlD1WfA$=pKgoega2a z+e%}YP0r7K%bwkmCWc|u7x!qyCC#@$vg_jkD)AjTswfS!EfZzF3AEH`V5Bb`;LTC+ z7XWjEB@RHZeIW48fDG<+brv`I1AjHf*Fqax;zmEyTo`V*u0hwZljDU~;covg%}2z? z9>6!)h%>DUd-)}~sv?uL(MF^6Hsl-C4jJDGnj%f19@a8(vXs>PIEUJNIp97(@noN! za96m(%Yg^5pQA9@c~k)_`*L8l%mcqN)&W~=xF17h4W%vlIV~t{$h&kX>;m>ND7=Yp z*;$+G@Xc}}6Fh;yKZ0D=C14JYZ5=U>>tNA9Qs9<6==8)s7+&~6#|QjEAcw$)`BIZ- z8BSbB8g1QfQwUFi<^`}J{M~5Z0yuSYXtxpF%9$=fHc*uw1{oK|^eu@HoMGlgIJu6? z)fA0$TnaRS=9I1I67~7Bk(c@t{9_TL4*SMn-~^;vE(f~tr9IgLT`_1?g*%Vw`oB7f zf6dpb`M1IbTXjaR^H%hwg}WqOtb1L;Xdmgr*V4 zNZJlG+D;SCRdCi|3TcmQvdg|0k@WRPKwn>OG9;s7scNw=+$?l9+v~3;$%Ee zsYNyLfmm_@(0qw{uC`n)Qa{`q>~I!$yO!(C-^T)PkymxMml9vpt;AE>+faMReL$zx zdI*>+=sgPG5VT+?Px(USh3-*1vwQW22p?lg@JEmK5}QFWiNOP&-`j!hk~Ru^PBmy{ zSSwI>H82lC|CvrT=(=cG7TGKt!H9~W1{Hy1$4RGsG)m!62cp+};NI-qhaJd!?mgpF zm)y~H%5LOxU=iB7vW=*~Q9(CSl5~$rG|dD}deCY~k|svz&9P!L;=2a-<=Mpsk+IJ*V{TYHGd zEk7f4nuK?#H#8UMRQz-Ln!ya`EvRXoJ=3=qSMj)->TASR46agqUAP*Bt3+Q$*)6DX zoqeKjEw1#qiuE<(O2E}_xH9@mou-+gT88^fSN$gcPrfUkw`7p8MARDMb*VLP z<9`JEyKYRRDZUj*__ zDRv`yIJYv$Z!#don_yp(umOM-04W*_> zWjS(jlRCP2&Y{so-sL-CD*-kUj1zs`&Cu1D66dSC8(NNDRcA8r7=nQ>gA1`AKwGlF zU%`5Voqz=ryTFmq6b1uFFscX-Xm_yFAMap^7yMMOd*HI0MqwSF$ZLRe@T@)7d*bdb z=r1lI8J2K2v2Zi&)@H%xEWbmcivoFRq1LN|JPkebcR`cqr(A^-n(%|dnW(@tW-V0q zrZ|>Zvi9ElXQtmf4gMX@lC>-DEV=KV^;1i6G|@9PoDps$oCz)g&H{HE+&Z}Ra1Kt* zrf(CN6>dCSJe(altKrh&iW$dlhg*SkYZ1O1{u=nV!Yzfn8sVD|Ux4d*EACloT3oVj z6$_pZosAeH9d`}^2Yk&Hz71hYvwkT4;i2$7L;mtLYu4Yhrewv+wRhZGQns4qxLo$N zWvlPH$;HanmQRDbX5G*^0kQ2 z;JyxF@&$xd@WY4V!w@zj95EEu5BVd8e2lRrObsW%>EVoUqu^rT;^9pEl4&be-al>q z`VEUJSPQ75xapu@!<8d^1KjU$J)C|iuEXG>;YJU+ zaWi2D4(@%p)7hYdlMhFEKDvqt!;`-yVfi!#xj2@9z^hEnFHBQ$H?2VtQBu5{1F1&ZYizAVB?iB#K5NW9}rz zs2}M8k>sO51NqsOlAJ6HZk z)|K~{m9D(nl(gcP?2GOzEnT^8-JR&34W_k2kEMcsCHv5m%U0jXR+p@1$<(JQG_sz% zJ*3YwJvXG^({E?2X2OT>ehlAsW{34T`0SOfvA2`|yc>{*mGG2V)$uEV2%aU@}ytN`( z`w0za{1R=7$Cift>Z6KZ^|u#thV_=luGTa)9jFyA^~^o1D$c$xW4yJe@PSRY&S_b< z@pSR%`xY+AvM;!Q`qb$&rdsbR$;`}Lo>@9`)}6|{N(+rhS~;vgU*ZiXtzf~^HB8XJ zU3w1V>=`B$KhA`?aA&KT&<8gFcVa7e@lS=u*e=MiQC(*a`E-5d&peclLmBq_?peih zZ_2rup>`(w0ux=EW}2=qS-pluVNUXRTcy(%FplGR6*ukYx-GJ%O`l<<-_N&DT`OC( z_`1xDxuIVuP&jj0*26PyuTZK$XC9vE8Zf~dCS4uYfW^V~Bc0zVHvalZ8U$E@Y_mCd zLMV>bABvkwKI3gBiesEjLO$gZajA4`_@@rVq3TM$YlrWXZwtjKs~z%HT^Sb>dY+B$ zA#U~+aqeWOqQPNNGE)4*xF*NI>YIb`L%1f#c(pnk;RkU|j&VGnh43}FCdUoMUyEyU z+))0a7=e-FhvMhqnjAlr|IuuLky8!DKZa{^s-gUk;F_FjD7{!HFmmdl^!MXgVi|q3<`+@;?GQ=l>#)lBDo$Wo-U>dR1uL(zhU=Qb$hK zv4zZ*_GB2#fTN#Xd8v%$4Ef4U`un9mH!Ang^)yz_^PoKm2&hBX^a)^#`6b=BPnZ9{ z{PHuHumNsXCiVw#)8U5e{=dZyr}iZC8e4i^eRu zGMuo0xvmUPS*)$TGMsUfap#rct8X52;EJ%a?+|z!P7bt@Sz>&L3H=xsG!IBMb+}r? zKHX14n&EIre>E6f5;uGY`;4JUG` + * + * 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_CUAV_7NANO_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_CUAV_7NANO_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 cuav_7-nano 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_ADCSRC 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 cuav_7-nano 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_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 | GPIO_PULLDOWN) /* 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 Not Used + * SPI4 is sensors3 + * 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_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */ +#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */ + +#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_PORTE|GPIO_PIN11) /* PE11 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN6) /* PI6 CAP1 */ +# define PROBE_10 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN7) /* PI7 CAP2 */ +# define PROBE_11 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN5) /* PI5 CAP3 */ +# define PROBE_12 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) /* PE6 CAP4 */ +# define PROBE_13 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 CAP5 */ +# define PROBE_14 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 CAP6 */ +# 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); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_10); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_11); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_12); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_13); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_14); } \ + } 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_CUAV_7NANO_INCLUDE_BOARD_H */ diff --git a/boards/cuav/7-nano/nuttx-config/include/board_dma_map.h b/boards/cuav/7-nano/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..fd284d631f47 --- /dev/null +++ b/boards/cuav/7-nano/nuttx-config/include/board_dma_map.h @@ -0,0 +1,71 @@ +/**************************************************************************** + * + * Copyright (c) 2024 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 IIM-42652 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 IIM-42652 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 BMI088 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 BMI088 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 RC */ + +// 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_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* 1 DMA2:61 BMP581 */ +#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* 2 DMA2:62 BMP581 */ + +#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 */ + +// 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/cuav/7-nano/nuttx-config/nsh/defconfig b/boards/cuav/7-nano/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..2105b231d119 --- /dev/null +++ b/boards/cuav/7-nano/nuttx-config/nsh/defconfig @@ -0,0 +1,327 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cuav/7-nano/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004c +CONFIG_CDCACM_PRODUCTSTR="PX4 CUAV 7 Nano" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="CUAV" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_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_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +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_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_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=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_NACTIVESOCKETS=16 +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_EMULATE_PAGE_SHIFT=6 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=6 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_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_PHY_POLLING=y +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_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=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_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +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_WATCHDOG=y diff --git a/boards/cuav/7-nano/nuttx-config/scripts/bootloader_script.ld b/boards/cuav/7-nano/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..7ce63598b5ac --- /dev/null +++ b/boards/cuav/7-nano/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016-2024 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 PX4 FMUV6X 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 PX4 FMUV6X 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/cuav/7-nano/nuttx-config/scripts/script.ld b/boards/cuav/7-nano/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..9b50b4b397a5 --- /dev/null +++ b/boards/cuav/7-nano/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016-2024 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 PX4 FMUV6X 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 PX4 FMUV6X 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/cuav/7-nano/pwm_voltage/CMakeLists.txt b/boards/cuav/7-nano/pwm_voltage/CMakeLists.txt new file mode 100644 index 000000000000..b1007be07b93 --- /dev/null +++ b/boards/cuav/7-nano/pwm_voltage/CMakeLists.txt @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2015-2024 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_module( + MODULE modules__pwm_voltage_apply + MAIN pwm_voltage_apply + + SRCS + pwm_voltage.cpp + DEPENDS + px4_work_queue + ) diff --git a/boards/cuav/7-nano/pwm_voltage/parameters.c b/boards/cuav/7-nano/pwm_voltage/parameters.c new file mode 100644 index 000000000000..847b32d83d3a --- /dev/null +++ b/boards/cuav/7-nano/pwm_voltage/parameters.c @@ -0,0 +1,44 @@ +/**************************************************************************** + * + * Copyright (c) 2024 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. + * + ****************************************************************************/ + +/** + * Control PWM output voltage + * + * Enable: PWM output voltage 5V + * Disable: PWM output voltage 3.3V + * + * @boolean + * @reboot_required true + * @group PWM Outputs + */ +PARAM_DEFINE_INT32(PWM_LEVEL_CONT, 0); diff --git a/boards/cuav/7-nano/pwm_voltage/pwm_voltage.cpp b/boards/cuav/7-nano/pwm_voltage/pwm_voltage.cpp new file mode 100644 index 000000000000..02f387f537a0 --- /dev/null +++ b/boards/cuav/7-nano/pwm_voltage/pwm_voltage.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (c) 2024 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 +#include + +#include "board_config.h" + +extern "C" int pwm_voltage_apply_main(int argc, char *argv[]) +{ + int32_t pwm_level_cont = 0; + + param_get(param_find("PWM_LEVEL_CONT"), &pwm_level_cont); + + if (pwm_level_cont != 0) { + VDD_5V_PWM_EN(true); + + } else { + VDD_5V_PWM_EN(false); + } + + return 0; +} diff --git a/boards/cuav/7-nano/src/CMakeLists.txt b/boards/cuav/7-nano/src/CMakeLists.txt new file mode 100644 index 000000000000..61c9937e4099 --- /dev/null +++ b/boards/cuav/7-nano/src/CMakeLists.txt @@ -0,0 +1,75 @@ +############################################################################ +# +# Copyright (c) 2024 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_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + 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 + 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/cuav/7-nano/src/board_config.h b/boards/cuav/7-nano/src/board_config.h new file mode 100644 index 000000000000..269a4890f361 --- /dev/null +++ b/boards/cuav/7-nano/src/board_config.h @@ -0,0 +1,408 @@ +/**************************************************************************** + * + * Copyright (c) 2024 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 + * + * CUAV 7-Nano internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +// /* Configuration ************************************************************************************/ + +/* 7-Nano GPIOs ***********************************************************************************/ + +/* LEDs */ +# 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 + +/* CAN Silence Silent mode control */ +#define GPIO_CAN1_SILENT_S0 /* PE2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN2) +#define GPIO_CAN2_SILENT_S1 /* PI8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN8) + +/* SPI */ + +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) + +/* I2C busses */ +#define BOARD_MTD_NUM_EEPROM 1 /* imu_eeprom */ + +#define GPIO_I2C4_DRDY1_ICP20100 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) + +/* + * 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, \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* 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_BATTERY_CURRENT_CHANNEL /* PB0 */ ADC1_CH(9) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_RSSI_IN_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC2 */ ADC1_CH(12) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC1_CH(13) +#define ADC_SERVO_VDD_SENSORS_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_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL) | \ + (1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL) | \ + (1 << ADC_SERVO_VDD_SENSORS_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) + +#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 UAVCAN_NUM_IFACES_RUNTIME 1 + +/* PE7 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 /* PE7 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN7) +#define GPIO_nARMED /* PE7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN7) +#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 14 + +/* PWM Power */ +#define GPIO_PWM_LEVEL_CONTROL /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) +#define VDD_5V_PWM_EN(on_true) px4_arch_gpiowrite(GPIO_PWM_LEVEL_CONTROL, (on_true)) + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_5V_PERIPH_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_PWM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_5V_HIPOWER_EN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET| GPIO_PORTG|GPIO_PIN10) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_EN, (on_true)) +#define VDD_PWM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_PWM_POWER_EN, (on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_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 3 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PC6 T8C1 */ GPIO_TIM3_CH1IN_3 + +/* RC Serial port */ + +#define RC_SERIAL_PORT "/dev/ttyS4" +#define RC_SERIAL_SINGLEWIRE + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 8 +#define INPUT_CAP1_CHANNEL 2 /* T8C2 */ +#define GPIO_INPUT_CAP1 GPIO_TIM8_CH2IN_2 /* PI6 */ + +#define INPUT_CAP2_TIMER 8 +#define INPUT_CAP2_CHANNEL 3 /* T8C3 */ +#define GPIO_INPUT_CAP2 GPIO_TIM8_CH3IN_2 /* PI7 */ + +#define INPUT_CAP3_TIMER 8 +#define INPUT_CAP3_CHANNEL 1 /* T8C1 */ +#define GPIO_INPUT_CAP3 GPIO_TIM8_CH1IN_2 /* PI5 */ + +#define INPUT_CAP4_TIMER 15 +#define INPUT_CAP4_CHANNEL 2 /* T4C1 */ +#define GPIO_INPUT_CAP4 GPIO_TIM4_CH1IN_2 /* PD12 */ + +#define INPUT_CAP5_TIMER 12 +#define INPUT_CAP5_CHANNEL 1 /* T12C1 */ +#define GPIO_INPUT_CAP5 GPIO_TIM12_CH1IN_2 /* PH6 */ + +#define INPUT_CAP6_TIMER 12 +#define INPUT_CAP6_CHANNEL 2 /* T12C2 */ +#define GPIO_INPUT_CAP6 GPIO_TIM12_CH2IN_2 /* PH9 */ + +/* 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) + +/* + * 7-nano 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_PORTC|GPIO_PIN6) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +// /* RSSI_IN */ +#define GPIO_RSSI_IN /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) + +#define BOARD_ADC_BRICK_VALID 1 +#define BOARD_NUMBER_BRICKS 1 + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_CAN2_SILENT_S1, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_5V_PERIPH_EN, \ + GPIO_VDD_PWM_POWER_EN, \ + GPIO_VDD_5V_HIPOWER_EN, \ + GPIO_ETH_POWER_EN, \ + SPI6_nRESET_EXTERNAL1, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_nARMED, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 1 + + +#define BOARD_NUM_IO_TIMERS 6 + +__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/cuav/7-nano/src/bootloader_main.c b/boards/cuav/7-nano/src/bootloader_main.c new file mode 100644 index 000000000000..cb7bdaf0835f --- /dev/null +++ b/boards/cuav/7-nano/src/bootloader_main.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2024 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); + +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/cuav/7-nano/src/can.c b/boards/cuav/7-nano/src/can.c new file mode 100644 index 000000000000..c134fd6fac10 --- /dev/null +++ b/boards/cuav/7-nano/src/can.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * + * Copyright (C) 2024 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 7-nano_can.c + * + * Board-specific CAN functions. + */ + +#ifdef CONFIG_CAN + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.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/cuav/7-nano/src/hw_config.h b/boards/cuav/7-nano/src/hw_config.h new file mode 100644 index 000000000000..a3ee52dea723 --- /dev/null +++ b/boards/cuav/7-nano/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,1500000" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 7000 +#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/cuav/7-nano/src/i2c.cpp b/boards/cuav/7-nano/src/i2c.cpp new file mode 100644 index 000000000000..2cb7b9a6a688 --- /dev/null +++ b/boards/cuav/7-nano/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusInternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/cuav/7-nano/src/init.c b/boards/cuav/7-nano/src/init.c new file mode 100644 index 000000000000..3bd2164622de --- /dev/null +++ b/boards/cuav/7-nano/src/init.c @@ -0,0 +1,274 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific 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 + +#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); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + board_control_spi_sensors_power(true, 0xffff); + VDD_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(io_timer_channel_get_gpio_output(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) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_PWM_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(); + + /* 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 */ + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/cuav/7-nano/src/led.c b/boards/cuav/7-nano/src/led.c new file mode 100644 index 000000000000..d6d8d9995621 --- /dev/null +++ b/boards/cuav/7-nano/src/led.c @@ -0,0 +1,236 @@ +/**************************************************************************** + * + * Copyright (c) 2024 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 fmu_led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + GPIO_nSAFETY_SWITCH_LED_OUT, // 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/cuav/7-nano/src/mtd.cpp b/boards/cuav/7-nano/src/mtd.cpp new file mode 100644 index 000000000000..f7e718e9181c --- /dev/null +++ b/boards/cuav/7-nano/src/mtd.cpp @@ -0,0 +1,102 @@ +/**************************************************************************** + * + * Copyright (C) 2024 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 +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V05A on FMUM native: 64K X 8, emulated as (1024 Blocks of 64) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +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 = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = (65536 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 2, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 2, + .entries = { + &fmum_fram, + &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/cuav/7-nano/src/sdio.c b/boards/cuav/7-nano/src/sdio.c new file mode 100644 index 000000000000..3776be5c0b1c --- /dev/null +++ b/boards/cuav/7-nano/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014-2024 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/cuav/7-nano/src/spi.cpp b/boards/cuav/7-nano/src/spi.cpp new file mode 100644 index 000000000000..f55a89563ca4 --- /dev/null +++ b/boards/cuav/7-nano/src/spi.cpp @@ -0,0 +1,60 @@ +/**************************************************************************** + * + * Copyright (C) 2020-2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortG, GPIO::Pin2}, SPI::DRDY{GPIO::PortG, GPIO::Pin3}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortI, GPIO::Pin11}), + // initSPIBus(SPI::Bus::SPI3,{ + // // no devices + // }) + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_BARO_DEVTYPE_BMP581, SPI::CS{GPIO::PortD, GPIO::Pin15}, SPI::DRDY{GPIO::PortG, GPIO::Pin1}), + }, {GPIO::PortI, GPIO::Pin11}), + 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}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/cuav/7-nano/src/timer_config.cpp b/boards/cuav/7-nano/src/timer_config.cpp new file mode 100644 index 000000000000..beee94fbf05c --- /dev/null +++ b/boards/cuav/7-nano/src/timer_config.cpp @@ -0,0 +1,89 @@ +/**************************************************************************** + * + * Copyright (C) 2024 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 + * + * TIM1_CH2 T FMU_CH7 + * TIM1_CH1 T FMU_CH8 + * + * TIM8_CH2 T FMU_CAP1 < Capture + * TIM8_CH3 T FMU_CAP2 < Capture + * TIM8_CH1 T FMU_CAP3 < Capture + * TIM15_CH2 T FMU_CAP4 < Capture + * TIM12_CH1 T FMU_CAP5 < Capture + * TIM12_CH2 T FMU_CAP6 < Capture + * + * + * 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::Timer1), + initIOTimer(Timer::Timer8), + initIOTimer(Timer::Timer15), + initIOTimer(Timer::Timer12), +}; + +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::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}), + initIOTimerChannelCapture(io_timers, {Timer::Timer8, Timer::Channel3}, {GPIO::PortI, GPIO::Pin7}), + initIOTimerChannelCapture(io_timers, {Timer::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}), + initIOTimerChannelCapture(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}), + initIOTimerChannelCapture(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannelCapture(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/cuav/7-nano/src/usb.c b/boards/cuav/7-nano/src/usb.c new file mode 100644 index 000000000000..48dbe2f6fde6 --- /dev/null +++ b/boards/cuav/7-nano/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_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); +}