Skip to content

Commit

Permalink
AP_Filesystem: implement format on littlefs
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Nov 27, 2024
1 parent 80027bb commit 29b5569
Show file tree
Hide file tree
Showing 2 changed files with 80 additions and 13 deletions.
82 changes: 75 additions & 7 deletions libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include "AP_Filesystem.h"
#include "AP_Filesystem_FlashMemory_LittleFS.h"
#include <GCS_MAVLink/GCS.h>

#include "lfs.h"

Expand Down Expand Up @@ -504,7 +505,7 @@ bool AP_Filesystem_FlashMemory_LittleFS::is_busy()
#else
uint8_t cmd = JEDEC_READ_STATUS;
dev->transfer(&cmd, 1, &status, 1);
return status & (JEDEC_STATUS_BUSY | JEDEC_STATUS_SRP0) != 0;
return (status & (JEDEC_STATUS_BUSY | JEDEC_STATUS_SRP0)) != 0;
#endif
}

Expand Down Expand Up @@ -562,7 +563,7 @@ void AP_Filesystem_FlashMemory_LittleFS::write_status_register(uint8_t reg, uint
dev->transfer(cmd, 3, nullptr, 0);
}

bool AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() {
uint32_t AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() {
if (!wait_until_device_is_ready()) {
return false;
}
Expand Down Expand Up @@ -644,7 +645,7 @@ bool AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() {
default:
hal.scheduler->delay(2000);
printf("Unknown SPI Flash 0x%08x\n", id);
return false;
return 0;
}

fs_cfg.read_size = page_size;
Expand All @@ -661,7 +662,7 @@ bool AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() {
// handle that right now
fs_cfg.cache_size = page_size;

return true;
return id;
}

bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() {
Expand All @@ -673,6 +674,8 @@ bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() {
return true;
}

EXPECT_DELAY_MS(3000);

fs_cfg.context = this;

fs_cfg.read = flashmem_read;
Expand All @@ -688,7 +691,9 @@ bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() {

dev_sem = dev->get_semaphore();

if (!find_block_size_and_count()) {
uint32_t id = find_block_size_and_count();

if (!id) {
mark_dead();
return false;
}
Expand All @@ -703,7 +708,13 @@ bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() {

if (lfs_mount(&fs, &fs_cfg) < 0) {
/* maybe not formatted? try formatting it */
printf("FlashMemory_LittleFS: formatting filesystem\n");
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash");
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
EXPECT_DELAY_MS(3000);
#else
EXPECT_DELAY_MS(30000);
#endif

if (lfs_format(&fs, &fs_cfg) < 0) {
/* cannot format either, give up */
mark_dead();
Expand All @@ -725,11 +736,68 @@ bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() {
lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY);
}
#endif

GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Mounted flash 0x%x as littlefs", unsigned(id));
mounted = true;
return true;
}

/*
format sdcard
*/
bool AP_Filesystem_FlashMemory_LittleFS::format(void)
{
WITH_SEMAPHORE(fs_sem);
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FlashMemory_LittleFS::format_handler, void));
// the format is handled asynchronously, we inform user of success
// via a text message. format_status can be polled for progress
format_status = FormatStatus::PENDING;
return true;
}

/*
format sdcard
*/
void AP_Filesystem_FlashMemory_LittleFS::format_handler(void)
{
if (format_status != FormatStatus::PENDING) {
return;
}
WITH_SEMAPHORE(fs_sem);
format_status = FormatStatus::IN_PROGRESS;
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash using littlefs");

int ret = lfs_format(&fs, &fs_cfg);

/* try mounting */
if (ret == LFS_ERR_OK) {
ret = lfs_mount(&fs, &fs_cfg);
}

#ifdef HAL_BOARD_STORAGE_DIRECTORY
// try to create the root storage folder. Ignore the error code in case
// the filesystem is corrupted or it already exists.
if (strlen(HAL_BOARD_STORAGE_DIRECTORY) > 0) {
lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY);
}
#endif

if (ret == LFS_ERR_OK) {
format_status = FormatStatus::SUCCESS;
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: OK");
} else {
format_status = FormatStatus::FAILURE;
mark_dead();
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: Failed (%d)", int(ret));
}
}

// returns true if we are currently formatting the SD card:
AP_Filesystem_Backend::FormatStatus AP_Filesystem_FlashMemory_LittleFS::get_format_status(void) const
{
// note that format_handler holds sem, so we can't take it here.
return format_status;
}

uint32_t AP_Filesystem_FlashMemory_LittleFS::lfs_block_and_offset_to_raw_flash_address(lfs_block_t index, lfs_off_t off)
{
return index * fs_cfg.block_size + off;
Expand Down
11 changes: 5 additions & 6 deletions libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,9 @@ class AP_Filesystem_FlashMemory_LittleFS : public AP_Filesystem_Backend

bool retry_mount(void) override;
void unmount(void) override;

/*
// format sdcard
// format flash. This is async, monitor get_format_status for progress
bool format(void) override;
*/
AP_Filesystem_Backend::FormatStatus get_format_status() const override;

int _flashmem_read(lfs_block_t block, lfs_off_t off, void* buffer, lfs_size_t size);
int _flashmem_prog(lfs_block_t block, lfs_off_t off, const void* buffer, lfs_size_t size);
Expand Down Expand Up @@ -90,6 +88,7 @@ class AP_Filesystem_FlashMemory_LittleFS : public AP_Filesystem_Backend

// Flag to denote that the underlying flash chip uses 32-bit addresses
bool use_32bit_address;
FormatStatus format_status;

int allocate_fd();
int free_fd(int fd);
Expand All @@ -98,7 +97,7 @@ class AP_Filesystem_FlashMemory_LittleFS : public AP_Filesystem_Backend

uint32_t lfs_block_and_offset_to_raw_flash_address(lfs_block_t block, lfs_off_t off = 0);
uint32_t lfs_block_to_raw_flash_page_index(lfs_block_t block);
bool find_block_size_and_count();
uint32_t find_block_size_and_count();
bool init_flash() WARN_IF_UNUSED;
bool write_enable() WARN_IF_UNUSED;
bool is_busy();
Expand All @@ -107,7 +106,7 @@ class AP_Filesystem_FlashMemory_LittleFS : public AP_Filesystem_Backend
void send_command_page(uint8_t command, uint32_t page);
bool wait_until_device_is_ready() WARN_IF_UNUSED;
void write_status_register(uint8_t reg, uint8_t bits);

void format_handler(void);
void mark_dead();
};

Expand Down

0 comments on commit 29b5569

Please sign in to comment.