mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
7fede90df3
Pixracer has FRAM on the same bus as the ms5611 and the FRAM ramtron driver does not use the same locking mechanism as other px4 SPI drivers. We need to disable interrupts during FRAM transfers to ensure we don't get FRAM corruption
48 lines
1.2 KiB
C++
48 lines
1.2 KiB
C++
|
|
|
|
#ifndef __AP_HAL_PX4_STORAGE_H__
|
|
#define __AP_HAL_PX4_STORAGE_H__
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include "AP_HAL_PX4_Namespace.h"
|
|
#include <systemlib/perf_counter.h>
|
|
|
|
#define PX4_STORAGE_SIZE HAL_STORAGE_SIZE
|
|
#define PX4_STORAGE_MAX_WRITE 512
|
|
#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:
|
|
int _fd;
|
|
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)));
|
|
volatile uint32_t _dirty_mask;
|
|
perf_counter_t _perf_storage;
|
|
perf_counter_t _perf_errors;
|
|
bool _have_mtd;
|
|
void _upgrade_to_mtd(void);
|
|
uint32_t _mtd_signature(void);
|
|
void _mtd_write_signature(void);
|
|
|
|
#if defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
|
|
irqstate_t irq_state;
|
|
#endif
|
|
void bus_lock(bool lock);
|
|
};
|
|
|
|
#endif // __AP_HAL_PX4_STORAGE_H__
|