mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: add get_storage_ptr method
This commit is contained in:
parent
b025c17ec4
commit
7a1044309c
|
@ -215,3 +215,16 @@ bool Storage::healthy(void)
|
|||
#endif
|
||||
return _initialised && AP_HAL::millis() - _last_empty_ms < 2000;
|
||||
}
|
||||
|
||||
/*
|
||||
get storage size and ptr
|
||||
*/
|
||||
bool Storage::get_storage_ptr(void *&ptr, size_t &size)
|
||||
{
|
||||
if (!_initialised) {
|
||||
return false;
|
||||
}
|
||||
ptr = _buffer;
|
||||
size = sizeof(_buffer);
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -39,6 +39,7 @@ public:
|
|||
|
||||
void _timer_tick(void) override;
|
||||
bool healthy(void) override;
|
||||
bool get_storage_ptr(void *&ptr, size_t &size) override;
|
||||
|
||||
private:
|
||||
volatile bool _initialised;
|
||||
|
|
Loading…
Reference in New Issue