Skip to content
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
Prev Previous commit
Next Next commit
AP_HAL_ChibiOS: Adding AP_PageEEPROM into AP_HAL_ChibiOS
  • Loading branch information
TOTON95 committed Jun 12, 2026
commit a046848af4d561a204b7fa1d85f74866cc6e3ecc
36 changes: 36 additions & 0 deletions libraries/AP_HAL_ChibiOS/Storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,10 @@ extern const AP_HAL::HAL& hal;
#define HAL_RAMTRON_ALLOW_FALLBACK 0
#endif

#ifndef HAL_PAGE_EEPROM_ALLOW_FALLBACK
#define HAL_PAGE_EEPROM_ALLOW_FALLBACK 0
#endif

void Storage::_storage_open(void)
{
if (_initialisedType != StorageBackend::None) {
Expand All @@ -74,6 +78,20 @@ void Storage::_storage_open(void)

#endif // HAL_WITH_RAMTRON

#if HAL_WITH_PAGE_EEPROM
if (pg_eeprom.init() && pg_eeprom.read(0, _buffer, CH_STORAGE_SIZE)) {
_save_backup();
_initialisedType = StorageBackend::Page_EEPROM;
::printf("Initialised Storage type=%d\n", _initialisedType);
return;
}

#if !HAL_PAGE_EEPROM_ALLOW_FALLBACK
AP_HAL::panic("Unable to init Page EEPROM storage");
#endif

#endif // HAL_WITH_PAGE_EEPROM

// allow for devices with no FRAM chip to fall through to other storage
#ifdef STORAGE_FLASH_PAGE
// load from storage backend
Expand Down Expand Up @@ -283,6 +301,14 @@ void Storage::_timer_tick(void)
}
#endif

#if HAL_WITH_PAGE_EEPROM
if (_initialisedType == StorageBackend::Page_EEPROM) {
if (pg_eeprom.write(CH_STORAGE_LINE_SIZE*i, tmpline, CH_STORAGE_LINE_SIZE)) {
write_ok = true;
}
}
#endif

#ifdef USE_POSIX
if ((_initialisedType == StorageBackend::SDCard) && log_fd != -1) {
uint32_t offset = CH_STORAGE_LINE_SIZE*i;
Expand Down Expand Up @@ -460,6 +486,11 @@ bool Storage::healthy(void)
if (_initialisedType == StorageBackend::SDCard) {
return log_fd != -1 || AP_HAL::millis() - _last_empty_ms < 30000U;
}
#endif
#if HAL_WITH_PAGE_EEPROM
if (_initialisedType == StorageBackend::Page_EEPROM) {
return AP_HAL::millis() - _last_empty_ms < 60000U;
}
#endif
return ((_initialisedType != StorageBackend::None) &&
(AP_HAL::millis() - _last_empty_ms < 2000u));
Expand All @@ -475,6 +506,11 @@ bool Storage::erase(void)
return AP_HAL::Storage::erase();
}
#endif
#if HAL_WITH_PAGE_EEPROM
if (_initialisedType == StorageBackend::Page_EEPROM) {
return AP_HAL::Storage::erase();
}
#endif
#ifdef USE_POSIX
if (_initialisedType == StorageBackend::SDCard) {
return AP_HAL::Storage::erase();
Expand Down
7 changes: 6 additions & 1 deletion libraries/AP_HAL_ChibiOS/Storage.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <AP_FlashStorage/AP_FlashStorage.h>
#include "hwdef/common/flash.h"
#include <AP_RAMTRON/AP_RAMTRON.h>
#include <AP_PageEEPROM/AP_PageEEPROM.h>

#define CH_STORAGE_SIZE HAL_STORAGE_SIZE

Expand All @@ -35,7 +36,7 @@
#else
#define CH_STORAGE_LINE_SHIFT 3
#endif
#elif defined(USE_POSIX) && !defined(HAL_WITH_RAMTRON)
#elif defined(USE_POSIX) && !defined(HAL_WITH_RAMTRON) && !defined(HAL_WITH_PAGE_EEPROM)
#define CH_STORAGE_LINE_SHIFT 9
#else
#define CH_STORAGE_LINE_SHIFT 3
Expand Down Expand Up @@ -71,6 +72,7 @@ class ChibiOS::Storage : public AP_HAL::Storage {
FRAM,
Flash,
SDCard,
Page_EEPROM,
};
StorageBackend _initialisedType = StorageBackend::None;
void _storage_create(void);
Expand Down Expand Up @@ -113,6 +115,9 @@ class ChibiOS::Storage : public AP_HAL::Storage {
#ifdef USE_POSIX
int log_fd;
#endif
#ifdef HAL_WITH_PAGE_EEPROM
AP_PageEEPROM pg_eeprom;
#endif
};

#endif // HAL_USE_EMPTY_STORAGE
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -867,6 +867,9 @@ def validate_flash_storage_size(self):
if self.intdefines.get('HAL_WITH_RAMTRON', 0) == 1:
# no check for RAMTRON storage
return
if self.intdefines.get('HAL_WITH_PAGE_EEPROM', 0) == 1:
# no check for PAGE_EEPROM storage
return
storage_flash_page = self.get_storage_flash_page()
pages = self.get_flash_pages_sizes()
page_size = pages[storage_flash_page] * 1024
Expand Down