mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added erase() method to Storage class
This commit is contained in:
parent
fd5ff97b59
commit
12b6f73d83
|
@ -0,0 +1,17 @@
|
|||
#include "AP_HAL.h"
|
||||
#include "Storage.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
/*
|
||||
default erase method
|
||||
*/
|
||||
bool AP_HAL::Storage::erase(void)
|
||||
{
|
||||
uint8_t blk[16] {};
|
||||
uint32_t ofs;
|
||||
for (ofs=0; ofs<HAL_STORAGE_SIZE; ofs += sizeof(blk)) {
|
||||
uint32_t n = MIN(sizeof(blk), HAL_STORAGE_SIZE - ofs);
|
||||
write_block(ofs, blk, n);
|
||||
}
|
||||
return true;
|
||||
}
|
|
@ -6,6 +6,7 @@
|
|||
class AP_HAL::Storage {
|
||||
public:
|
||||
virtual void init() = 0;
|
||||
virtual bool erase();
|
||||
virtual void read_block(void *dst, uint16_t src, size_t n) = 0;
|
||||
virtual void write_block(uint16_t dst, const void* src, size_t n) = 0;
|
||||
virtual void _timer_tick(void) {};
|
||||
|
|
Loading…
Reference in New Issue