Browse Source

AP_HAL_Linux: add get_storage_ptr method

gps-1.3.1
bugobliterator 3 years ago committed by Andrew Tridgell
parent
commit
f57f106c7f
  1. 13
      libraries/AP_HAL_Linux/Storage.cpp
  2. 2
      libraries/AP_HAL_Linux/Storage.h

13
libraries/AP_HAL_Linux/Storage.cpp

@ -266,3 +266,16 @@ void Storage::_timer_tick(void) @@ -266,3 +266,16 @@ void Storage::_timer_tick(void)
}
}
}
/*
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;
}

2
libraries/AP_HAL_Linux/Storage.h

@ -32,6 +32,8 @@ public: @@ -32,6 +32,8 @@ public:
void write_dword(uint16_t loc, uint32_t value);
void write_block(uint16_t dst, const void* src, size_t n) override;
bool get_storage_ptr(void *&ptr, size_t &size) override;
virtual void _timer_tick(void) override;
protected:

Loading…
Cancel
Save