mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: add get_storage_ptr method
This commit is contained in:
parent
f57f106c7f
commit
09096cb355
|
@ -388,4 +388,15 @@ bool Storage::healthy(void)
|
|||
return AP_HAL::millis() - _last_empty_ms < 2000;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
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;
|
||||
}
|
||||
|
|
|
@ -28,6 +28,7 @@ public:
|
|||
void init() override {}
|
||||
void read_block(void *dst, uint16_t src, size_t n) override;
|
||||
void write_block(uint16_t dst, const void* src, size_t n) override;
|
||||
bool get_storage_ptr(void *&ptr, size_t &size) override;
|
||||
|
||||
void _timer_tick(void) override;
|
||||
bool healthy(void) override;
|
||||
|
|
Loading…
Reference in New Issue