移植PX4固件到自制NuttX操作系统飞控板的方法
- 找到使用相同(或型号相似)CPU类型的现有目标并进行复制
- 飞控板的配置文件夹结构
- firmware.prototype文件
- default.px4board文件
- bootloader.px4board文件
- nuttx-config/bootloader/defconfig文件
- nuttx-config/nsh/defconfig文件
- nuttx-config/include/board.h文件
- nuttx-config/include/board_dma_map.h文件
- nuttx-config/scripts/bootloader_script.ld文件和script.ld文件
- src文件夹
- extras文件夹
- init/rc.board_sensors文件
- init/rc.board_defaults文件
- 编写驱动需要知识量太多,不知如何修改怎么办
- 编译BootLoader并烧录进自己的飞控板
为了将NuttX操作系统上的PX4固件移植到新的硬件,新的硬件必须被NuttX操作系统支持。
如果是已经支持的硬件(商用的飞控板已经使用了该主控芯片并且支持PX4固件),那么直接在该固件上进行修改即可。
如果是未支持的硬件,NuttX项目维护了一个优秀的移植指南,用于将NuttX移植到一个新的硬件平台。
NuttX Porting Guide
以下教程中需要移植的飞控使用STM32H7系列芯片,它是是已经支持的硬件。
找到使用相同(或型号相似)CPU类型的现有目标并进行复制
所有飞控板的配置文件,包括链接器脚本和其他所需设置,位于/boards文件夹中,各个供应商和各个飞控板位于目录板/供应商/型号/
即boards/VENDOR/MODEL/
中。
进入飞控固件文件夹,在boards文件夹中建立UCAS/YanQi文件夹,UCAS是我的学校名称,YanQi是我的飞控板名称,pixhawk标准飞控板供应商家的fmu-v6u飞控板也使用的是STM32H7系列芯片,所以可以作为被移植对象,复制其内容到我的飞控板文件夹。
cd Firmware/
mkdir boards/UCAS/YanQi
cp -r boards/px4/fmu-v6u/* boards/UCAS/YanQi
接下来需要浏览boards/UCAS/YanQi下的所有文件,并根据飞控板硬件进行设置。
飞控板的配置文件夹结构
飞控板的配置文件夹结构为下列所示。
YanQi
├─extras
| └─UCAS_YanQi_bootloader.bin
├─init
| ├─rc.board_defaults
| └─rc.board_sensors
├─nuttx-config
| ├─bootloader
| | └─defconfig
| ├─include
| | ├─board.h
| | └─board_dma_map.h
| ├─nsh
| | └─defconfig
| ├─scripts
| | ├─bootloader_script.ld
| | └─script.ld
| ├─src
| └─Kconfig
├─src
| ├─board_config.h
| ├─bootloader_main.c
| ├─CMakeLists.txt
| ├─hw_config.h
| ├─i2c.cpp
| ├─init.c
| ├─...
| └─usb.c
├─bootloader.px4board
├─default.px4board
└─firmware.prototype
firmware.prototype文件
修改飞控板ID、名称和闪存大小,主要修改board_id
、description
、YanQi
、image_maxsize
,这里可以根据自己的需要进行设置。
如果修改board_id
,那么src文件夹下的hw_config.h文件中的#define BOARD_TYPE
也需要修改为对应的ID号。
{"board_id": 719,"magic": "PX4FWv1","description": "Firmware for the YanQi FlightControl board","image": "","build_time": 0,"summary": "YanQi","version": "0.1","image_size": 0,"image_maxsize": 1966080,"git_identity": "","board_revision": 0
}
default.px4board文件
最常使用的文件,它负责配置每个串口的映射,配置哪些源码被编译到飞控固件中。
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_COMMON_BAROMETERS=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=yCONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_BAROMETER_BMP388=yCONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=yCONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PWM_OUT_SIM=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=yCONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=yCONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=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
CONFIG_EXAMPLES_FAKE_GPS=y
bootloader.px4board文件
配置哪些源码被编译到bootloader中,一般不需要修改。
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROMFSROOT=""
nuttx-config/bootloader/defconfig文件
通过make UCAS_YanQi menuconfig
命令配置NuttX操作系统,调整主控芯片型号,配置外围设备(UART、SPI、I2C、ADC)。
运行menuconfig
命令需要先安装KConfig,安装方法如下,在任意文件夹路径下运行均可。
git clone https://bitbucket.org/nuttx/tools.git
cd tools/kconfig-frontends
sudo apt install gperf flex bison
sudo apt-get install libncurses5-dev
autoreconf -f -i
./configure --enable-mconf --disable-nconf --disable-gconf --enable-qconf --prefix=/usr
make
sudo make install
之后使用以下命令即可进行GUI界面配置。
make UCAS_YanQi_default menuconfig
nuttx-config/bootloader/defconfig文件配置的是bootloader中需要调用的底层资源,比如最基础的USB驱动、TIM定时器驱动、系统控制台System Console的驱动等。
注意修改CONFIG_ARCH_BOARD_CUSTOM_DIR
的路径地址为自己飞控板的路径。
CONFIG_CDCACM_PRODUCTSTR
和CONFIG_CDCACM_VENDORSTR
可以修改为任意名称,但是对应的CONFIG_CDCACM_PRODUCTID
和CONFIG_CDCACM_VENDORID
必须设置为官方供应商,不然地面站无法识别。
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DEV_CONSOLE is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_SPI_EXCHANGE is not set
# CONFIG_STM32H7_SYSCFG is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/UCAS/YanQi/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_INITTHREAD_PRIORITY=254
CONFIG_BOARD_LATE_INITIALIZE=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0050
CONFIG_CDCACM_PRODUCTSTR="PX4 YanQi FlightControl Board"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="UCAS"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_PTHREAD=y
CONFIG_EXPERIMENTAL=y
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LIB_BOARDCTL=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SPI=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=19
CONFIG_START_MONTH=7
CONFIG_START_YEAR=2024
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_USART3=y
CONFIG_SYSTEMTICK_HOOK=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGINT_CHAR=0x03
CONFIG_TTY_SIGTSTP=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=300
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="bootloader_main"
nuttx-config/nsh/defconfig文件
nuttx-config/nsh/defconfig文件配置的是飞控固件中需要调用的底层资源,比如串口驱动、SPI驱动、I2C驱动等等。
注意修改CONFIG_ARCH_BOARD_CUSTOM_DIR
的路径地址为自己飞控板的路径。
CONFIG_CDCACM_PRODUCTSTR
和CONFIG_CDCACM_VENDORSTR
可以修改为任意名称,但是对应的CONFIG_CDCACM_PRODUCTID
和CONFIG_CDCACM_VENDORID
必须设置为官方供应商,不然地面站无法识别。
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/UCAS/YanQi/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95751
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0050
CONFIG_CDCACM_PRODUCTSTR="PX4 YanQi FlightControl Board"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="UCAS"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_IOB_NBUFFERS=24
CONFIG_IOB_NCHAINS=24
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_IOB=y
CONFIG_MM_REGIONS=4
# CONFIG_MTD=y
# CONFIG_MTD_BYTE_WRITE=y
# CONFIG_MTD_PARTITION=y
# CONFIG_MTD_PROGMEM=y
# CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
# CONFIG_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=19
CONFIG_START_MONTH=7
CONFIG_START_YEAR=2024
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_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_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_SDMMC1=y
CONFIG_STM32H7_SDMMC1_DMA=y
CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024
# CONFIG_STM32H7_SDMMC2=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
CONFIG_STM32H7_SPI3=y
CONFIG_STM32H7_SPI3_DMA=y
CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
# CONFIG_STM32H7_SPI5=y
# CONFIG_STM32H7_SPI6=y
# CONFIG_STM32H7_SPI6_DMA=y
# CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
# CONFIG_STM32H7_TIM12=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_TIM5=yCONFIG_STM32H7_USART1=y #ttyS0
CONFIG_STM32H7_USART2=y #ttyS1
CONFIG_STM32H7_USART3=y #ttyS2
CONFIG_STM32H7_UART4=y #ttyS3
CONFIG_STM32H7_UART5=y #ttyS4
CONFIG_STM32H7_UART7=y #ttyS5# CONFIG_STM32H7_USART_BREAKS=y
# CONFIG_STM32H7_USART_INVERT=y
# CONFIG_STM32H7_USART_SINGLEWIRE=y
# CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=3000CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART3_SERIAL_CONSOLE=yCONFIG_UART4_BAUD=921600
CONFIG_UART4_RXBUFSIZE=3000
CONFIG_UART4_TXBUFSIZE=1200CONFIG_UART5_BAUD=57600
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_TXBUFSIZE=1500CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_TXBUFSIZE=3000CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
CONFIG_WQUEUE_NOTIFIER=y
nuttx-config/include/board.h文件
配置NuttX操作系统中的时钟和引脚,对于所有具有多功能引脚(比如STM32中的有些引脚既可以作为UART也可以作为普通GPIO)的外围设备,NuttX需要知道每个引脚的设定功能,它们在芯片特定的引脚映射头文件stm32h7x3xx_pinmap.h中定义。
引脚映射头文件stm32h7x3xx_pinmap.h
这里举个例子,比如STM32的USART1可以使用多个GPIO引脚组实现,比如PA14PA15、PA9PA10、PB4PB5三个组,在芯片特定的引脚映射头文件stm32h7x3xx_pinmap.h中对此就有三组不同的定义。
#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_100MHz|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN15)
#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_SPEED_100MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
#define GPIO_USART1_RX_3 (GPIO_ALT|GPIO_AF7|GPIO_SPEED_100MHz|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN7)
#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF4|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN14)
#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN9)
#define GPIO_USART1_TX_3 (GPIO_ALT|GPIO_AF7|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN6)
如果选择PA9PA10这个GPIO引脚组进行串口通信,就在board.h文件中定义GPIO_USART1_RX为相对应的GPIO_USART1_RX_2标识符值,GPIO_USART1_TX为相对应的GPIO_USART1_TX_2标识符值。
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */
下面是完整的board.h文件代码。
#ifndef __NUTTX_CONFIG_PX4_FMU_V6U_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_PX4_FMU_V6U_INCLUDE_BOARD_H/************************************************************************************* Included Files************************************************************************************/#include "board_dma_map.h"#include <nuttx/config.h>#ifndef __ASSEMBLY__
# include <stdint.h>
#endif#include "stm32_rcc.h"
#include "stm32_sdmmc.h"/************************************************************************************* Pre-processor Definitions************************************************************************************//* Clocking *************************************************************************/
/* The px4_fmu-v6u board provides the following clock sources:** X1: 16 MHz crystal for HSE** So we have these clock source available within the STM32** HSI: 16 MHz RC factory-trimmed* HSE: 16 MHz crystal for HSE*/#define STM32_BOARD_XTAL 16000000ul#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768/* Main PLL Configuration.** PLL source is HSE = 16,000,000** PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN* Subject to:** 1 <= PLLM <= 63* 4 <= PLLN <= 512* 150 MHz <= PLL_VCOL <= 420MHz* 192 MHz <= PLL_VCOH <= 836MHz** SYSCLK = PLL_VCO / PLLP* CPUCLK = SYSCLK / D1CPRE* Subject to** PLLP1 = {2, 4, 6, 8, ..., 128}* PLLP2,3 = {2, 3, 4, ..., 128}* CPUCLK <= 480 MHz*/#define STM32_BOARD_USEHSE#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR** PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz** PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz*/#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \RCC_PLLCFGR_DIVP1EN | \RCC_PLLCFGR_DIVQ1EN | \RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60)
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)/* PLL2 */#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \RCC_PLLCFGR_DIVP2EN | \RCC_PLLCFGR_DIVQ2EN | \RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4)
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48)
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2)
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)/* PLL3 */#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \RCC_PLLCFGR_DIVQ3EN)
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4)
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48)
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4)
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4)
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)/* SYSCLK = PLL1P = 480MHz* CPUCLK = SYSCLK / 1 = 480 MHz*/#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)/* Configure Clock Assignments *//* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240*/#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler *//* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)/* Timer clock frequencies *//* Timers driven from APB1 will be twice PCLK1 */#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)/* Timers driven from APB2 will be twice PCLK2 */#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)/* Kernel Clock Configuration** Note: look at Table 54 in ST Manual*//* I2C123 clock source */#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI/* I2C4 clock source */#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI/* SPI123 clock source */#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2/* SPI45 clock source */#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2/* SPI6 clock source */#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2/* USB 1 and 2 clock source */#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3/* ADC 1 2 3 clock source */#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2/* CAN FD 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 PX4 FMUV6U board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and* LED_RED a Red LED, that can be controlled by software.** If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.* The following definitions are used to access individual LEDs.*//* LED index values for use with board_userled() *//* LED definitions ******************************************************************/
/* The px4_fmu-v6u 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_2 /* PA10 */
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */
#define GPIO_USART1_CK GPIO_USART1_CK /* PB6 */#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_CK GPIO_USART2_CK_2 /* PD7 */#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_CK GPIO_USART3_CK_3 /* PD10 */#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
// 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_3 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
// #define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */
// #define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */// #define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
// #define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 *//* CAN** CAN1 is routed to transceiver.* CAN2 is routed to transceiver.*/
// #define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
// #define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 *//* SPI* SPI1 is sensors1* SPI2 is sensors2* SPI3 is sensors3* SPI4 is Not Used* SPI5 is FRAM* SPI6 is EXTERNAL1**/#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2 /* PC1 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PC10 */#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PB6 */
#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_1) /* PG13 *//* I2C** The optional _GPIO configurations allow the I2C driver to manually* reset the bus to clear stuck slaves. They match the pin configuration,* but are normally-high GPIOs.**/#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11)// #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)/* SDMMC** VDD 3.3* GND* SDMMC1_CK PC12* SDMMC1_CMD PD2* SDMMC1_D0 PC8* SDMMC1_D1 PC9* SDMMC1_D2 PC10* SDMMC1_D3 PC11*/// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */
// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */
// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */
// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */
// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */
// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 *//* USB** OTG_FS_DM PA11* OTG_FS_DP PA12* VBUS PA9*//* Board provides GPIO or other Hardware for signaling to timing analyzer */#if defined(CONFIG_BOARD_USE_PROBES)
# include "stm32_gpio.h"
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */# define PROBE_INIT(mask) \do { \if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \} while(0)# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif#endif /*__NUTTX_CONFIG_PX4_FMU_V6U_INCLUDE_BOARD_H */
nuttx-config/include/board_dma_map.h文件
用于配置DMA。DMA用来提供在外设和存储器之间或者存储器和存储器之间的高速数据传输。无须CPU的干预,通过DMA数据可以快速地移动,这就节省了CPU的资源来做其他操作。
/*
* DMA channel define reference to stm32h7x3xx_dmamux.h
*/
#pragma once// DMAMUX1
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */// DMAMUX2
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* DMA1:61 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* DMA1:62 */#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 *///TODO UART
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_1 /*DMA2:41*/
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_1 /*DMA2:42*/#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* DMA2:45 */
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* DMA2:46 */#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 */
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 */#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_0 /* DMA1:65 */
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5RX_0 /* DMA1:66 */// #define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_0 /* DMA1:79 */
// #define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_0 /* DMA1:80 */
nuttx-config/scripts/bootloader_script.ld文件和script.ld文件
用于分配内存地址和大小,如果需要使用外部Flash芯片的话需要进行修改。以下是关于内存地址分配部分的代码。
MEMORY
{itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64Kflash (rx) : ORIGIN = 0x08000000, LENGTH = 128Kdtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64Kdtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64Ksram (rwx) : ORIGIN = 0x24000000, LENGTH = 512Ksram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128Ksram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128Ksram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32Ksram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64Kbbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
src文件夹
遍历src下的所有文件,并根据需要修改它们。
board_config.h文件是一些LED灯定义、ADC采样定义。
bootloader_main.c文件是bootloader的主函数。
hw_config.h是硬件的一些参数配置。
init.c是飞控固件的初始化主函数。
i2c.cpp、led.c、sdio.c、spi.cpp、timer_config.cpp、usb.c是相关驱动。
extras文件夹
存放生成的二进制固件文件UCAS_YanQi_bootloader.bin。
init/rc.board_sensors文件
启动连接到板上的传感器。
#!/bin/sh
#
# PX4 YanQi specific board sensors init
#------------------------------------------------------------------------------board_adc start# Internal SPI bus MPU6500
mpu6500 -R 0 -s start# Internal SPI bus ICM-42688P
icm42688p -R 0 -s start# Internal SPI bus BMI088 accel/gyro
bmi088 -A -R 0 -s start
bmi088 -G -R 0 -s start# internal baro
bmp388 -I -a 0x76 start
init/rc.board_defaults文件
可以在这里配置一些参数的初始值,这样一烧录完固件就具有了参数值,不需要再去QGC里面修改了。
#!/bin/sh
#
# PX4 YanQi board specific defaults
#------------------------------------------------------------------------------
param set-default SYS_HAS_MAG 0
param set-default IMU_GYRO_RATEMAX 2000
编写驱动需要知识量太多,不知如何修改怎么办
多看boards文件夹中其他的飞控板的驱动例程,一般飞控板用到的驱动都是可以在其他的飞控板的驱动中找到,只需要进行挪用整合修改即可。
编译BootLoader并烧录进自己的飞控板
在Firmware文件夹中输入命令即可对BootLoader和固件进行编译。
make UCAS_YanQi_bootloader
make UCAS_YanQi_default
没有安装烧录工具的先安装dfu-util烧录工具包。
sudo apt install dfu-util
按住飞控板上的BOOT键同时将USB线插入飞控板,进入DFU模式,运行命令即可进行BootLoader烧录。
dfu-util -a 0 --dfuse-address 0x08000000 -D ./build/UCAS_YanQi_bootloader/UCAS_YanQi_bootloader.bin
之后使用QGC安装UCAS_YanQi_default.px4飞控固件即可。
参考资料:
Firmware Porting Steps
Manufacturer’s PX4 Board Support Guide
PX4-20-支持新的控制器硬件