mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_HAL_ChibiOS: add get_storage_ptr method
This commit is contained in:
parent
6d4ac999d0
commit
b025c17ec4
@ -468,4 +468,18 @@ bool Storage::erase(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
get storage size and ptr
|
||||
*/
|
||||
bool Storage::get_storage_ptr(void *&ptr, size_t &size)
|
||||
{
|
||||
if (_initialisedType==StorageBackend::None) {
|
||||
return false;
|
||||
}
|
||||
ptr = _buffer;
|
||||
size = sizeof(_buffer);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
#endif // HAL_USE_EMPTY_STORAGE
|
||||
|
@ -46,6 +46,7 @@ public:
|
||||
|
||||
void _timer_tick(void) override;
|
||||
bool healthy(void) override;
|
||||
bool get_storage_ptr(void *&ptr, size_t &size) override;
|
||||
|
||||
private:
|
||||
enum class StorageBackend: uint8_t {
|
||||
|
Loading…
Reference in New Issue
Block a user