mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
HAL_PX4: use eeprom on PX4 FMUv1 as well
this means we no longer store params on SD at all
This commit is contained in:
parent
ae4f368f16
commit
64fbadcc21
@ -14,8 +14,8 @@
|
||||
using namespace PX4;
|
||||
|
||||
/*
|
||||
This stores 'eeprom' data on the SD card, with a 4k size, and a
|
||||
in-memory buffer. This keeps the latency down.
|
||||
This stores eeprom data in the PX4 MTD interface with a 4k size, and
|
||||
a in-memory buffer. This keeps the latency and devices IOs down.
|
||||
*/
|
||||
|
||||
// name the storage file after the sketch so you can use the same sd
|
||||
@ -23,8 +23,9 @@ using namespace PX4;
|
||||
#define STORAGE_DIR "/fs/microsd/APM"
|
||||
#define OLD_STORAGE_FILE STORAGE_DIR "/" SKETCHNAME ".stg"
|
||||
#define OLD_STORAGE_FILE_BAK STORAGE_DIR "/" SKETCHNAME ".bak"
|
||||
#define MTD_PARAMS_FILE "/fs/mtd_params"
|
||||
#define MTD_PARAMS_FILE "/fs/mtd"
|
||||
#define MTD_SIGNATURE 0x14012014
|
||||
#define MTD_SIGNATURE_OFFSET (8192-4)
|
||||
#define STORAGE_RENAME_OLD_FILE 0
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -37,35 +38,17 @@ PX4Storage::PX4Storage(void) :
|
||||
{
|
||||
}
|
||||
|
||||
void PX4Storage::_storage_create(void)
|
||||
{
|
||||
mkdir(STORAGE_DIR, 0777);
|
||||
unlink(_storage_name);
|
||||
int fd = open(_storage_name, O_RDWR|O_CREAT, 0666);
|
||||
if (fd == -1) {
|
||||
hal.scheduler->panic("Failed to create " OLD_STORAGE_FILE);
|
||||
}
|
||||
for (uint16_t loc=0; loc<sizeof(_buffer); loc += PX4_STORAGE_MAX_WRITE) {
|
||||
if (write(fd, &_buffer[loc], PX4_STORAGE_MAX_WRITE) != PX4_STORAGE_MAX_WRITE) {
|
||||
hal.scheduler->panic("Error filling " OLD_STORAGE_FILE);
|
||||
}
|
||||
}
|
||||
// ensure the directory is updated with the new size
|
||||
fsync(fd);
|
||||
close(fd);
|
||||
}
|
||||
|
||||
/*
|
||||
get signature from bytes at offset 8192-4
|
||||
get signature from bytes at offset MTD_SIGNATURE_OFFSET
|
||||
*/
|
||||
uint32_t PX4Storage::_mtd_signature(void)
|
||||
{
|
||||
int mtd_fd = open(_storage_name, O_RDONLY);
|
||||
int mtd_fd = open(MTD_PARAMS_FILE, O_RDONLY);
|
||||
if (mtd_fd == -1) {
|
||||
hal.scheduler->panic("Failed to open " MTD_PARAMS_FILE);
|
||||
}
|
||||
uint32_t v;
|
||||
if (lseek(mtd_fd, 8192-4, SEEK_SET) != 8192-4) {
|
||||
if (lseek(mtd_fd, MTD_SIGNATURE_OFFSET, SEEK_SET) != MTD_SIGNATURE_OFFSET) {
|
||||
hal.scheduler->panic("Failed to seek in " MTD_PARAMS_FILE);
|
||||
}
|
||||
if (read(mtd_fd, &v, sizeof(v)) != sizeof(v)) {
|
||||
@ -76,16 +59,16 @@ uint32_t PX4Storage::_mtd_signature(void)
|
||||
}
|
||||
|
||||
/*
|
||||
put signature bytes at offset 8192-4
|
||||
put signature bytes at offset MTD_SIGNATURE_OFFSET
|
||||
*/
|
||||
void PX4Storage::_mtd_write_signature(void)
|
||||
{
|
||||
int mtd_fd = open(_storage_name, O_WRONLY);
|
||||
int mtd_fd = open(MTD_PARAMS_FILE, O_WRONLY);
|
||||
if (mtd_fd == -1) {
|
||||
hal.scheduler->panic("Failed to open " MTD_PARAMS_FILE);
|
||||
}
|
||||
uint32_t v = MTD_SIGNATURE;
|
||||
if (lseek(mtd_fd, 8192-4, SEEK_SET) != 8192-4) {
|
||||
if (lseek(mtd_fd, MTD_SIGNATURE_OFFSET, SEEK_SET) != MTD_SIGNATURE_OFFSET) {
|
||||
hal.scheduler->panic("Failed to seek in " MTD_PARAMS_FILE);
|
||||
}
|
||||
if (write(mtd_fd, &v, sizeof(v)) != sizeof(v)) {
|
||||
@ -107,7 +90,7 @@ void PX4Storage::_upgrade_to_mtd(void)
|
||||
return;
|
||||
}
|
||||
|
||||
int mtd_fd = open(_storage_name, O_WRONLY);
|
||||
int mtd_fd = open(MTD_PARAMS_FILE, O_WRONLY);
|
||||
if (mtd_fd == -1) {
|
||||
hal.scheduler->panic("Unable to open MTD for upgrade");
|
||||
}
|
||||
@ -139,83 +122,35 @@ void PX4Storage::_storage_open(void)
|
||||
struct stat st;
|
||||
_have_mtd = (stat(MTD_PARAMS_FILE, &st) == 0);
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
// FMUv2 should always have /fs/mtd_params
|
||||
// PX4 should always have /fs/mtd_params
|
||||
if (!_have_mtd) {
|
||||
hal.scheduler->panic("Failed to find " MTD_PARAMS_FILE);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (_have_mtd) {
|
||||
_storage_name = MTD_PARAMS_FILE;
|
||||
} else {
|
||||
// NuttX seems to be happier not having the extra directory
|
||||
// entries for mapping the case of filenames. Keeping it all
|
||||
// uppercase seems to reduce meta-data corruption when rebooting
|
||||
// while writing
|
||||
if (strcmp(SKETCHNAME, "ArduPlane") == 0) {
|
||||
_storage_name = STORAGE_DIR "/" "PLANE.STG";
|
||||
} else if (strcmp(SKETCHNAME, "ArduCopter") == 0) {
|
||||
_storage_name = STORAGE_DIR "/" "COPTER.STG";
|
||||
} else if (strcmp(SKETCHNAME, "APMrover2") == 0) {
|
||||
_storage_name = STORAGE_DIR "/" "ROVER.STG";
|
||||
} else {
|
||||
_storage_name = OLD_STORAGE_FILE;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
cope with upgrading from OLD_STORAGE_FILE to MTD
|
||||
*/
|
||||
if (_have_mtd) {
|
||||
bool good_signature = (_mtd_signature() == MTD_SIGNATURE);
|
||||
if (stat(OLD_STORAGE_FILE, &st) == 0) {
|
||||
if (good_signature) {
|
||||
bool good_signature = (_mtd_signature() == MTD_SIGNATURE);
|
||||
if (stat(OLD_STORAGE_FILE, &st) == 0) {
|
||||
if (good_signature) {
|
||||
#if STORAGE_RENAME_OLD_FILE
|
||||
rename(OLD_STORAGE_FILE, OLD_STORAGE_FILE_BAK);
|
||||
rename(OLD_STORAGE_FILE, OLD_STORAGE_FILE_BAK);
|
||||
#endif
|
||||
} else {
|
||||
_upgrade_to_mtd();
|
||||
}
|
||||
}
|
||||
if (!good_signature) {
|
||||
_mtd_write_signature();
|
||||
} else {
|
||||
_upgrade_to_mtd();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
NuttX is not properly case insensitive on VFAT. We will create
|
||||
the file as uppercase, but if the file already exists we need
|
||||
to rename it first
|
||||
*/
|
||||
if (!_have_mtd && stat(_storage_name, &st) == -1 && stat(OLD_STORAGE_FILE, &st) == 0) {
|
||||
::printf("Renaming %s to %s\n", OLD_STORAGE_FILE, _storage_name);
|
||||
if (rename(OLD_STORAGE_FILE, _storage_name) != 0) {
|
||||
unlink(OLD_STORAGE_FILE);
|
||||
}
|
||||
if (!good_signature) {
|
||||
_mtd_write_signature();
|
||||
}
|
||||
|
||||
_dirty_mask = 0;
|
||||
int fd = open(_storage_name, O_RDONLY);
|
||||
int fd = open(MTD_PARAMS_FILE, O_RDONLY);
|
||||
if (fd == -1) {
|
||||
_storage_create();
|
||||
fd = open(_storage_name, O_RDONLY);
|
||||
if (fd == -1) {
|
||||
hal.scheduler->panic("Failed to open " OLD_STORAGE_FILE);
|
||||
}
|
||||
hal.scheduler->panic("Failed to open " MTD_PARAMS_FILE);
|
||||
}
|
||||
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
|
||||
close(fd);
|
||||
_storage_create();
|
||||
fd = open(_storage_name, O_RDONLY);
|
||||
if (fd == -1) {
|
||||
hal.scheduler->panic("Failed to open " OLD_STORAGE_FILE);
|
||||
}
|
||||
ssize_t ret;
|
||||
if ((ret=read(fd, _buffer, sizeof(_buffer))) != sizeof(_buffer)) {
|
||||
::printf("read: %d errno=%d\n", (int)ret, (int)errno);
|
||||
hal.scheduler->panic("Failed to read " OLD_STORAGE_FILE);
|
||||
}
|
||||
hal.scheduler->panic("Failed to read " MTD_PARAMS_FILE);
|
||||
}
|
||||
close(fd);
|
||||
_initialised = true;
|
||||
@ -334,7 +269,7 @@ void PX4Storage::_timer_tick(void)
|
||||
perf_begin(_perf_storage);
|
||||
|
||||
if (_fd == -1) {
|
||||
_fd = open(_storage_name, O_WRONLY);
|
||||
_fd = open(MTD_PARAMS_FILE, O_WRONLY);
|
||||
if (_fd == -1) {
|
||||
perf_end(_perf_storage);
|
||||
perf_count(_perf_errors);
|
||||
|
@ -31,7 +31,6 @@ public:
|
||||
void _timer_tick(void);
|
||||
|
||||
private:
|
||||
const char *_storage_name;
|
||||
int _fd;
|
||||
volatile bool _initialised;
|
||||
void _storage_create(void);
|
||||
|
Loading…
Reference in New Issue
Block a user