2 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 12 #include <nuttx/progmem.h> 26 #define STORAGE_DIR "/fs/microsd/APM" 28 #define MTD_PARAMS_FILE "/fs/mtd" 32 extern "C" int mtd_main(
int,
char **);
35 _perf_storage(perf_alloc(PC_ELAPSED,
"APM_storage")),
36 _perf_errors(perf_alloc(PC_COUNT,
"APM_storage_errors"))
55 #ifdef SAVE_STORAGE_FILE 56 fd =
open(SAVE_STORAGE_FILE, O_WRONLY|O_CREAT|O_TRUNC, 0644);
58 write(fd, _buffer,
sizeof(_buffer));
60 ::printf(
"Saved storage file %s\n", SAVE_STORAGE_FILE);
75 uint16_t
end = loc + length;
85 if (loc >=
sizeof(_buffer)-(n-1)) {
89 memcpy(dst, &_buffer[loc], n);
94 if (loc >=
sizeof(_buffer)-(n-1)) {
97 if (memcmp(src, &_buffer[loc], n) != 0) {
99 memcpy(&_buffer[loc], src, n);
111 #if !USE_FLASH_STORAGE 130 if (i == VRBRAIN_STORAGE_NUM_LINES) {
138 #if USE_FLASH_STORAGE 147 #if !USE_FLASH_STORAGE 150 #if defined (CONFIG_ARCH_BOARD_PX4FMU_V4) 161 irq_state = irqsave();
163 irqrestore(irq_state);
175 if (
lseek(
_fd, ofs, SEEK_SET) != ofs) {
183 ssize_t ret =
write(
_fd, &_buffer[ofs], VRBRAIN_STORAGE_LINE_SIZE);
186 if (ret != VRBRAIN_STORAGE_LINE_SIZE) {
201 printf(
"mtd: started OK\n");
203 printf(
"mtd: readtest OK\n");
215 const uint16_t chunk_size = 128;
216 for (uint16_t ofs=0; ofs<
sizeof(_buffer); ofs += chunk_size) {
218 ssize_t ret =
read(fd, &_buffer[ofs], chunk_size);
220 if (ret != chunk_size) {
221 ::printf(
"storage read of %u bytes at %u to %p failed - got %d errno=%d\n",
222 (
unsigned)
sizeof(_buffer), (
unsigned)ofs, &_buffer[ofs], (
int)ret, (
int)
errno);
229 #else // USE_FLASH_STORAGE 234 void VRBRAINStorage::_flash_load(
void)
236 _flash_page = up_progmem_npages() - 2;
237 if (up_progmem_pagesize(_flash_page) != 128*1024U ||
238 up_progmem_pagesize(_flash_page+1) != 128*1024U) {
240 up_progmem_pagesize(_flash_page),
241 up_progmem_pagesize(_flash_page+1));
244 printf(
"Storage: Using flash pages %u and %u\n", _flash_page, _flash_page+1);
246 if (!_flash.init()) {
254 void VRBRAINStorage::_flash_write(uint16_t line)
267 bool VRBRAINStorage::_flash_write_data(uint8_t sector, uint32_t offset,
const uint8_t *data, uint16_t length)
269 size_t base_address = up_progmem_getaddress(_flash_page+sector);
270 bool ret = up_progmem_write(base_address+offset, data, length) == length;
271 if (!ret && _flash_erase_ok()) {
277 bool ok = _flash.re_initialise();
278 printf(
"Storage: failed at %u:%u for %u - re-init %u\n",
279 sector, offset, length, (
unsigned)ok);
288 bool VRBRAINStorage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
290 size_t base_address = up_progmem_getaddress(_flash_page+sector);
291 const uint8_t *b = ((
const uint8_t *)base_address)+offset;
292 memcpy(data, b, length);
299 bool VRBRAINStorage::_flash_erase_sector(uint8_t sector)
301 return up_progmem_erasepage(_flash_page+sector) > 0;
307 bool VRBRAINStorage::_flash_erase_ok(
void)
312 #endif // USE_FLASH_STORAGE 315 #endif // CONFIG_HAL_BOARD
int printf(const char *fmt,...)
bool get_soft_armed() const
void read_block(void *dst, uint16_t src, size_t n)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
void _timer_tick(void) override
void write_block(uint16_t dst, const void *src, size_t n)
perf_counter_t _perf_storage
static const AP_HAL::HAL & hal
#define VRBRAIN_STORAGE_LINE_SIZE
int mtd_main(int, char **)
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
bool get(uint16_t bit) const
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments)
int close(int fileno)
POSIX Close a file with fileno handel.
void _mtd_write(uint16_t line)
uint32_t _last_re_init_ms
#define VRBRAIN_STORAGE_NUM_LINES
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
volatile bool _initialised
int errno
Note: fdevopen assigns stdin,stdout,stderr.
#define VRBRAIN_STORAGE_LINE_SHIFT
perf_counter_t _perf_errors
void panic(const char *errormsg,...) FMT_PRINTF(1
void _mark_dirty(uint16_t loc, uint16_t length)
static void sensor_config_error(const char *reason)