Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Clean up and extend RAMTRON driver #13621

Closed
wants to merge 26 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
ce15de4
AP_RAMTRON: Interpret RDID reg based on manufacturer
nexton-winjeel Oct 4, 2019
df07aec
AP_RAMTRON: Get RAMTRON driver working
nexton-winjeel Feb 20, 2020
1d7e3f9
AP_HAL_ChibiOS: Use updated RAMTRON driver
nexton-winjeel Feb 20, 2020
7b6b4ba
AP_Param: Print bad header values if setup() fails
nexton-winjeel Feb 20, 2020
95abc66
AP_Param: Add static assert on NVM struct sizes
nexton-winjeel Mar 2, 2020
18299f6
AP_RAMTRON: Ensure RAMTRON write enable fields are set correctly
nexton-winjeel Oct 7, 2019
598376c
AP_HAL_ChibiOS: Record which storage backend is in use
nexton-winjeel Oct 7, 2019
56e9070
AP_HAL_ChibiOS: Add hwdef param to panic if FRAM init fails
nexton-winjeel Oct 7, 2019
f67b742
AP_HAL_ChibiOS: Print console message to indicate which storage type …
nexton-winjeel Oct 7, 2019
bd1f132
AP_HAL_ChibiOS: Remove #error pragma for when no storage backend is d…
nexton-winjeel Oct 7, 2019
b3d2ec3
AP_RAMTRON: Ensure status register write doesn't overwrite WriteEnabl…
nexton-winjeel Oct 7, 2019
aa373d2
AP_RAMTRON: Tidy up const correctness
nexton-winjeel Oct 7, 2019
03105c6
AP_RAMTRON: Use enum class for RDID_type enum
nexton-winjeel Feb 20, 2020
ff29e83
AP_HAL_ChibiOS: Remove inline initialisation of VLAs
nexton-winjeel Feb 20, 2020
9855f26
AP_HAL_ChibiOS: Use ::printf() rather than HAL console
nexton-winjeel Feb 24, 2020
a149a76
AP_HAL_ChibiOS: Invert naming and logic of FALLBACK define
nexton-winjeel Feb 24, 2020
eb80ffe
AP_RAMTRON: Revert read() and write() to return bool
nexton-winjeel Mar 3, 2020
84008d9
AP_HAL_ChibiOS: Use updated RAMTRON driver read() and write()
nexton-winjeel Mar 2, 2020
d54fff0
AP_RAMTRON: Clarify chip select settings for reads and writes
nexton-winjeel Mar 3, 2020
1b00b26
Plane: Add better logging to explain why parameters are being erased
nexton-winjeel Feb 20, 2020
c7aac16
Rover: Add better logging to explain why parameters are being erased
nexton-winjeel Mar 6, 2020
09bbb92
Tracker: Add better logging to explain why parameters are being erased
nexton-winjeel Mar 6, 2020
6042ac8
Copter: Add better logging to explain why parameters are being erased
nexton-winjeel Mar 6, 2020
77aea19
Sub: Add better logging to explain why parameters are being erased
nexton-winjeel Mar 6, 2020
2dc533a
AP_RAMTRON: Add retries to init()
nexton-winjeel Mar 3, 2020
528fe35
AP_RAMTRON: Add retries to read()
nexton-winjeel Mar 3, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 9 additions & 3 deletions APMrover2/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -739,10 +739,16 @@ void Rover::load_parameters(void)
AP_HAL::panic("Bad var table");
}

if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {
uint8_t loadErr = !g.format_version.load();
bool isNewFirmware = g.format_version != Parameters::k_format_version;
if (loadErr || isNewFirmware) {

// erase all parameters
hal.console->printf("Firmware change: erasing EEPROM...\n");
if (loadErr) {
hal.console->printf("Couldn't load params: erasing params...\n");
} else {
hal.console->printf("Firmware change: erasing params...\n");
}
StorageManager::erase();
AP_Param::erase_all();

Expand Down
11 changes: 8 additions & 3 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -487,11 +487,16 @@ const AP_Param::Info Tracker::var_info[] = {

void Tracker::load_parameters(void)
{
if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {
uint8_t loadErr = !g.format_version.load();
bool isNewFirmware = g.format_version != Parameters::k_format_version;
if (loadErr || isNewFirmware) {

// erase all parameters
hal.console->printf("Firmware change: erasing EEPROM...\n");
if (loadErr) {
hal.console->printf("Couldn't load params: erasing params...\n");
} else {
hal.console->printf("Firmware change: erasing params...\n");
}
StorageManager::erase();
AP_Param::erase_all();

Expand Down
11 changes: 8 additions & 3 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1065,11 +1065,16 @@ void Copter::load_parameters(void)
ahrs.set_correct_centrifugal(false);
hal.util->set_soft_armed(false);

if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {
uint8_t loadErr = !g.format_version.load();
bool isNewFirmware = g.format_version != Parameters::k_format_version;
if (loadErr || isNewFirmware) {

// erase all parameters
hal.console->printf("Firmware change: erasing EEPROM...\n");
if (loadErr) {
hal.console->printf("Couldn't load params: erasing params...\n");
} else {
hal.console->printf("Firmware change: erasing params...\n");
}
StorageManager::erase();
AP_Param::erase_all();

Expand Down
11 changes: 8 additions & 3 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1326,11 +1326,16 @@ void Plane::load_parameters(void)
hal.console->printf("Bad parameter table\n");
AP_HAL::panic("Bad parameter table");
}
if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

once we move this logic up into AP_Vehicle we could consider this change, but for now it just makes the vehicles different from each other

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would you prefer me to remove this change, or to incorporate it into the other vehicles?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Made this change in all vehicles.

uint8_t loadErr = !g.format_version.load();
bool isNewFirmware = g.format_version != Parameters::k_format_version;
if (loadErr || isNewFirmware) {

// erase all parameters
hal.console->printf("Firmware change: erasing EEPROM...\n");
if (loadErr) {
hal.console->printf("Couldn't load params: erasing params...\n");
} else {
hal.console->printf("Firmware change: erasing params...\n");
}
StorageManager::erase();
AP_Param::erase_all();

Expand Down
13 changes: 9 additions & 4 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -662,17 +662,22 @@ void Sub::load_parameters()
ahrs.set_correct_centrifugal(false);
hal.util->set_soft_armed(false);

if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {
uint8_t loadErr = !g.format_version.load();
bool isNewFirmware = g.format_version != Parameters::k_format_version;
if (loadErr || isNewFirmware) {

// erase all parameters
hal.console->printf("Firmware change: erasing EEPROM...\n");
if (loadErr) {
hal.console->printf("Couldn't load params: erasing params...\n");
} else {
hal.console->printf("Firmware change: erasing params...\n");
}
StorageManager::erase();
AP_Param::erase_all();

// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
hal.console->println("done.");
hal.console->printf("done.\n");
}

uint32_t before = AP_HAL::micros();
Expand Down
138 changes: 79 additions & 59 deletions libraries/AP_HAL_ChibiOS/Storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,64 +44,72 @@ extern const AP_HAL::HAL& hal;

void Storage::_storage_open(void)
{
if (_initialised) {
if (_initialisedType != StorageBackend::None) {
return;
}

#ifdef USE_POSIX
// if we have failed filesystem init don't try again
if (log_fd == -1) {
return;
}
#endif

_dirty_mask.clearall();

#if HAL_WITH_RAMTRON
using_fram = fram.init();
if (using_fram) {
if (!fram.read(0, _buffer, CH_STORAGE_SIZE)) {
if (fram.init()) {
if (fram.read(0, _buffer, CH_STORAGE_SIZE)) {
_save_backup();
_initialisedType = StorageBackend::FRAM;
::printf("Initialised Storage type=%d\n", _initialisedType);
return;
}
_save_backup();
_initialised = true;
return;
}
// allow for FMUv3 with no FRAM chip, fall through to flash storage

#if defined(HAL_RAMTRON_ALLOW_FALLBACK) && !HAL_RAMTRON_ALLOW_FALLBACK
AP_HAL::panic("Unable to init RAMTRON storage");
#endif

#endif // HAL_WITH_RAMTRON

// allow for devices with no FRAM chip to fall through to other storage
#ifdef STORAGE_FLASH_PAGE
// load from storage backend
_flash_load();
// load from storage backend
_flash_load();
_save_backup();
_initialisedType = StorageBackend::Flash;
#elif defined(USE_POSIX)
// allow for fallback to microSD based storage
sdcard_retry();
// if we have failed filesystem init don't try again
if (log_fd == -1) {
return;
}

log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
if (log_fd == -1) {
::printf("open failed of " HAL_STORAGE_FILE "\n");
return;
}
int ret = AP::FS().read(log_fd, _buffer, CH_STORAGE_SIZE);
if (ret < 0) {
::printf("read failed for " HAL_STORAGE_FILE "\n");
AP::FS().close(log_fd);
log_fd = -1;
return;
}
// pre-fill to full size
if (AP::FS().lseek(log_fd, ret, SEEK_SET) != ret ||
AP::FS().write(log_fd, &_buffer[ret], CH_STORAGE_SIZE-ret) != CH_STORAGE_SIZE-ret) {
::printf("setup failed for " HAL_STORAGE_FILE "\n");
AP::FS().close(log_fd);
log_fd = -1;
return;
}
using_filesystem = true;
// allow for fallback to microSD based storage
if (sdcard_retry()) {
log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
if (log_fd == -1) {
::printf("open failed of " HAL_STORAGE_FILE "\n");
return;
}
int ret = AP::FS().read(log_fd, _buffer, CH_STORAGE_SIZE);
if (ret < 0) {
::printf("read failed for " HAL_STORAGE_FILE "\n");
AP::FS().close(log_fd);
log_fd = -1;
return;
}
// pre-fill to full size
if (AP::FS().lseek(log_fd, ret, SEEK_SET) != ret ||
AP::FS().write(log_fd, &_buffer[ret], CH_STORAGE_SIZE-ret) != CH_STORAGE_SIZE-ret) {
::printf("setup failed for " HAL_STORAGE_FILE "\n");
AP::FS().close(log_fd);
log_fd = -1;
return;
}
_save_backup();
_initialisedType = StorageBackend::SDCard;
}
#endif

_save_backup();
_initialised = true;
if (_initialisedType != StorageBackend::None) {
::printf("Initialised Storage type=%d\n", _initialisedType);
} else {
AP_HAL::panic("Unable to init Storage backend");
}
}

/*
Expand All @@ -113,11 +121,12 @@ void Storage::_save_backup(void)
{
#ifdef USE_POSIX
// allow for fallback to microSD based storage
sdcard_retry();
int fd = AP::FS().open(HAL_STORAGE_BACKUP_FILE, O_WRONLY|O_CREAT|O_TRUNC);
if (fd != -1) {
AP::FS().write(fd, _buffer, CH_STORAGE_SIZE);
AP::FS().close(fd);
if (sdcard_retry()) {
int fd = AP::FS().open(HAL_STORAGE_BACKUP_FILE, O_WRONLY|O_CREAT|O_TRUNC);
if (fd != -1) {
AP::FS().write(fd, _buffer, CH_STORAGE_SIZE);
AP::FS().close(fd);
}
}
#endif
}
Expand All @@ -144,7 +153,7 @@ void Storage::_mark_dirty(uint16_t loc, uint16_t length)

void Storage::read_block(void *dst, uint16_t loc, size_t n)
{
if (loc >= sizeof(_buffer)-(n-1)) {
if ((n > sizeof(_buffer)) || (loc > (sizeof(_buffer) - n))) {
return;
}
_storage_open();
Expand All @@ -153,7 +162,7 @@ void Storage::read_block(void *dst, uint16_t loc, size_t n)

void Storage::write_block(uint16_t loc, const void *src, size_t n)
{
if (loc >= sizeof(_buffer)-(n-1)) {
if ((n > sizeof(_buffer)) || (loc > (sizeof(_buffer) - n))) {
return;
}
if (memcmp(src, &_buffer[loc], n) != 0) {
Expand All @@ -165,7 +174,7 @@ void Storage::write_block(uint16_t loc, const void *src, size_t n)

void Storage::_timer_tick(void)
{
if (!_initialised) {
if (_initialisedType == StorageBackend::None) {
return;
}
if (_dirty_mask.empty()) {
Expand All @@ -187,7 +196,7 @@ void Storage::_timer_tick(void)
}

#if HAL_WITH_RAMTRON
if (using_fram) {
if (_initialisedType == StorageBackend::FRAM) {
if (fram.write(CH_STORAGE_LINE_SIZE*i, &_buffer[CH_STORAGE_LINE_SIZE*i], CH_STORAGE_LINE_SIZE)) {
_dirty_mask.clear(i);
}
Expand All @@ -196,7 +205,7 @@ void Storage::_timer_tick(void)
#endif

#ifdef USE_POSIX
if (using_filesystem && log_fd != -1) {
if ((_initialisedType == StorageBackend::SDCard) && log_fd != -1) {
uint32_t offset = CH_STORAGE_LINE_SIZE*i;
if (AP::FS().lseek(log_fd, offset, SEEK_SET) != offset) {
return;
Expand All @@ -213,8 +222,10 @@ void Storage::_timer_tick(void)
#endif

#ifdef STORAGE_FLASH_PAGE
// save to storage backend
_flash_write(i);
if (_initialisedType == StorageBackend::Flash) {
// save to storage backend
_flash_write(i);
}
#endif
}

Expand All @@ -229,10 +240,10 @@ void Storage::_flash_load(void)
::printf("Storage: Using flash pages %u and %u\n", _flash_page, _flash_page+1);

if (!_flash.init()) {
AP_HAL::panic("unable to init flash storage");
AP_HAL::panic("Unable to init flash storage");
}
#else
AP_HAL::panic("unable to init storage");
AP_HAL::panic("Unable to init storage");
#endif
}

Expand Down Expand Up @@ -284,24 +295,32 @@ bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *
*/
bool Storage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
{
#ifdef STORAGE_FLASH_PAGE
size_t base_address = hal.flash->getpageaddr(_flash_page+sector);
const uint8_t *b = ((const uint8_t *)base_address)+offset;
memcpy(data, b, length);
return true;
#else
return false;
#endif
}

/*
callback to erase flash sector
*/
bool Storage::_flash_erase_sector(uint8_t sector)
{
#ifdef STORAGE_FLASH_PAGE
for (uint8_t i=0; i<STORAGE_FLASH_RETRIES; i++) {
if (hal.flash->erasepage(_flash_page+sector)) {
return true;
}
hal.scheduler->delay(1);
}
return false;
#else
return false;
#endif
}

/*
Expand All @@ -319,7 +338,8 @@ bool Storage::_flash_erase_ok(void)
*/
bool Storage::healthy(void)
{
return _initialised && AP_HAL::millis() - _last_empty_ms < 2000;
return ((_initialisedType != StorageBackend::None) &&
(AP_HAL::millis() - (_last_empty_ms < 2000)));
}

/*
Expand All @@ -328,12 +348,12 @@ bool Storage::healthy(void)
bool Storage::erase(void)
{
#if HAL_WITH_RAMTRON
if (using_fram) {
if (_initialisedType == StorageBackend::FRAM) {
return AP_HAL::Storage::erase();
}
#endif
#ifdef USE_POSIX
if (using_filesystem) {
if (_initialisedType == StorageBackend::SDCard) {
return AP_HAL::Storage::erase();
}
#endif
Expand Down
10 changes: 7 additions & 3 deletions libraries/AP_HAL_ChibiOS/Storage.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,13 @@ class ChibiOS::Storage : public AP_HAL::Storage {
bool healthy(void) override;

private:
volatile bool _initialised;
enum class StorageBackend: uint8_t {
None,
FRAM,
Flash,
SDCard,
};
volatile StorageBackend _initialisedType = StorageBackend::None;
void _storage_create(void);
void _storage_open(void);
void _save_backup(void);
Expand Down Expand Up @@ -79,10 +85,8 @@ class ChibiOS::Storage : public AP_HAL::Storage {

#if HAL_WITH_RAMTRON
AP_RAMTRON fram;
bool using_fram;
#endif
#ifdef USE_POSIX
bool using_filesystem;
int log_fd;
#endif
};
Expand Down
Loading