mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
b0832e6c15
ready for multiple backends
42 lines
1.1 KiB
C++
42 lines
1.1 KiB
C++
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include "AP_HAL_PX4_Namespace.h"
|
|
#include <systemlib/perf_counter.h>
|
|
#include <AP_Common/Bitmask.h>
|
|
|
|
#define PX4_STORAGE_SIZE HAL_STORAGE_SIZE
|
|
#define PX4_STORAGE_LINE_SHIFT 9
|
|
#define PX4_STORAGE_LINE_SIZE (1<<PX4_STORAGE_LINE_SHIFT)
|
|
#define PX4_STORAGE_NUM_LINES (PX4_STORAGE_SIZE/PX4_STORAGE_LINE_SIZE)
|
|
|
|
class PX4::PX4Storage : public AP_HAL::Storage {
|
|
public:
|
|
PX4Storage();
|
|
|
|
void init() {}
|
|
void read_block(void *dst, uint16_t src, size_t n);
|
|
void write_block(uint16_t dst, const void* src, size_t n);
|
|
|
|
void _timer_tick(void);
|
|
|
|
private:
|
|
volatile bool _initialised;
|
|
void _storage_create(void);
|
|
void _storage_open(void);
|
|
void _mark_dirty(uint16_t loc, uint16_t length);
|
|
uint8_t _buffer[PX4_STORAGE_SIZE] __attribute__((aligned(4)));
|
|
Bitmask _dirty_mask{PX4_STORAGE_NUM_LINES};
|
|
perf_counter_t _perf_storage;
|
|
perf_counter_t _perf_errors;
|
|
|
|
int _fd = -1;
|
|
void _mtd_load(void);
|
|
void _mtd_write(uint16_t line);
|
|
|
|
#if defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
|
|
irqstate_t irq_state;
|
|
#endif
|
|
void bus_lock(bool lock);
|
|
};
|