ardupilot/libraries/AP_HAL/Storage.h

16 lines
462 B
C
Raw Permalink Normal View History

#pragma once
#include <stdint.h>
#include "AP_HAL_Namespace.h"
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) {};
virtual bool healthy(void) { return true; }
2021-11-08 10:19:20 -04:00
virtual bool get_storage_ptr(void *&ptr, size_t &size) { return false; }
};