mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
feat(boards): add W25N NAND flash support with littlefs
The kakuteh7mini ships with a W25N01GV (1Gbit/128MB) SPI NAND flash on SPI1, but the board init was treating SPI1 as an MMC/SD slot and the W25N driver was not enabled. Enable the chip and use it for logging: - spi.cpp: register the device as SPIDEV_FLASH(0) instead of SPIDEV_MMCSD(0) - init.c: initialize the W25N MTD driver, register /dev/mtd0, mount littlefs at /fs/flash with autoformat, and print the flash geometry on boot for verification. - nuttx defconfig: enable CONFIG_MTD_W25N, CONFIG_FS_LITTLEFS, SPI1 DMA + DMAMUX1, drop the unused RAMTRON config. - board_dma_map.h: define DMAMAP_SPI1_RX/TX for the SPI1 DMA channels. - default.px4board: set CONFIG_BOARD_ROOT_PATH to /fs/flash. - rc.board_defaults: drop the SDLOG_BACKEND=0 override that was disabling logging entirely and the COM_ARM_SDCARD override (the flash logging replaces the need for an SD card). Set SDLOG_MAX_SIZE=30 so a few recent logs fit within the 128 MB flash.
This commit is contained in:
parent
18493222ed
commit
7f76b71526
@ -1,5 +1,6 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ROOT_PATH="/fs/flash"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
|
||||
@ -32,11 +32,10 @@ param set-default CBRK_BUZZER 782090
|
||||
|
||||
param set-default IMU_GYRO_RATEMAX 2000
|
||||
|
||||
# W25N NAND flash with littlefs (128 MB): small log file size so we can keep
|
||||
# a few recent logs. Default SDLOG_ROTATE=90 keeps at least 10% free during
|
||||
# writing (no bad block management yet, so avoid hammering the flash near full).
|
||||
param set-default SDLOG_MAX_SIZE 30
|
||||
|
||||
# Store missions in RAM
|
||||
param set-default SYS_DM_BACKEND 1
|
||||
|
||||
# Ignore that there is no SD card
|
||||
param set-default COM_ARM_SDCARD 0
|
||||
|
||||
# Disable logging
|
||||
param set-default SDLOG_BACKEND 0
|
||||
|
||||
@ -33,6 +33,9 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1 */
|
||||
|
||||
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2 */
|
||||
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2 */
|
||||
|
||||
|
||||
@ -98,6 +98,10 @@ CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_LITTLEFS=y
|
||||
CONFIG_FS_LITTLEFS_CACHE_SIZE_FACTOR=1
|
||||
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
|
||||
CONFIG_FS_LITTLEFS_READ_SIZE_FACTOR=1
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
@ -126,7 +130,8 @@ CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_PROGMEM=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
# CONFIG_MTD_RAMTRON is not set
|
||||
CONFIG_MTD_W25N=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
@ -135,7 +140,7 @@ CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_MMCSDSPIPORTNO=1
|
||||
# CONFIG_NSH_MMCSDSPIPORTNO is not set
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
@ -148,9 +153,6 @@ CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
|
||||
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
@ -188,6 +190,7 @@ CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_DMAMUX1=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
@ -201,6 +204,8 @@ CONFIG_STM32H7_SDMMC1=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=4096
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI4=y
|
||||
CONFIG_STM32H7_SPI4_DMA=y
|
||||
@ -244,4 +249,5 @@ CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_W25N_SPIFREQUENCY=104000000
|
||||
CONFIG_WATCHDOG=y
|
||||
|
||||
@ -59,6 +59,8 @@
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/mm/gran.h>
|
||||
#include <nuttx/mtd/mtd.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_uart.h>
|
||||
#include <arch/board/board.h>
|
||||
@ -231,15 +233,58 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
// MARK: this will *not* work as the minis have a W25N NAND flash chip
|
||||
/* Get the SPI port for the microSD slot */
|
||||
struct spi_dev_s *spi_dev = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO);
|
||||
#ifdef CONFIG_MTD_W25N
|
||||
/* Initialize W25N01GV NAND Flash on SPI1 */
|
||||
struct spi_dev_s *spi1 = stm32_spibus_initialize(1);
|
||||
|
||||
if (!spi_dev) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
|
||||
led_on(LED_BLUE);
|
||||
if (!spi1) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI1 for W25N\n");
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
struct mtd_dev_s *mtd = w25n_initialize(spi1, 0);
|
||||
|
||||
if (!mtd) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize W25N MTD driver\n");
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
int ret = register_mtddriver("/dev/mtd0", mtd, 0755, NULL);
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to register MTD driver: %d\n", ret);
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
syslog(LOG_INFO, "[boot] W25N MTD registered at /dev/mtd0\n");
|
||||
|
||||
struct mtd_geometry_s geo;
|
||||
|
||||
if (mtd->ioctl(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&geo)) == 0) {
|
||||
syslog(LOG_INFO, "[boot] W25N: %lu erase blocks, %lu bytes/block, %lu total bytes\n",
|
||||
(unsigned long)geo.neraseblocks,
|
||||
(unsigned long)geo.erasesize,
|
||||
(unsigned long)geo.neraseblocks * (unsigned long)geo.erasesize);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_FS_LITTLEFS
|
||||
ret = nx_mount("/dev/mtd0", CONFIG_BOARD_ROOT_PATH, "littlefs", 0, "autoformat");
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to mount littlefs: %d\n", ret);
|
||||
led_on(LED_RED);
|
||||
|
||||
} else {
|
||||
syslog(LOG_INFO, "[boot] LittleFS mounted at %s\n", CONFIG_BOARD_ROOT_PATH);
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
up_udelay(20);
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
|
||||
@ -37,7 +37,7 @@
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(SPIDEV_MMCSD(0), SPI::CS{GPIO::PortA, GPIO::Pin4})
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortA, GPIO::Pin4}) // W25N01GV NAND Flash
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}),
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user