APM:Libraries
Storage.h
Go to the documentation of this file.
1 /* -*- Mode: C++; indent-tabs-mode: nil; c-basic-offset: 2 -*- */
2 /*
3  * Storage.h --- AP_HAL_F4Light storage driver.
4 
5  based on:
6 
7  * Copyright (C) 2013, Virtualrobotix.com Roberto Navoni , Emile
8  * All Rights Reserved.
9  *
10  * This software is released under the "BSD3" license. Read the file
11  * "LICENSE" for more information.
12  *
13  * Written by Roberto Navoni <info@virtualrobotix.com>, 11 January 2013
14  */
15 
16 
17 // another way - https://habrahabr.ru/post/262163/
18 
19 #pragma once
20 
21 #include <AP_HAL/AP_HAL.h>
24 #include <hal.h>
25 
26 // read is quite expensive operation because requires scan of 16K RAM
27 // we have a lot of unused CCM memory so lets cache data in RAM
28 #define EEPROM_CACHED
29 // write is very expensive operation so move out it to separate thread
30 #define WRITE_IN_THREAD
31 
33 {
34 public:
35  Storage();
36  void init();
37  static void late_init(bool defer);
38 
39  void read_block(void *dst, uint16_t src, size_t n);
40  void write_block(uint16_t dst, const void* src, size_t n);
41 
42 // just for us
43  static uint8_t read_byte(uint16_t loc);
44  static void write_byte(uint16_t loc, uint8_t value);
45 
46  typedef struct {
47  uint16_t loc;
48  uint16_t val;
49  } Item;
50 #define EEPROM_QUEUE_LEN 256
51 
52 private:
53  static void _write_byte(uint16_t loc, uint8_t value);
54  static uint8_t _read_byte(uint16_t loc);
55 
56  static void write_word(uint16_t loc, uint16_t value);
57 
58  static void do_on_disarm();
59  static bool write_deferred;
60 
61  static void error_parse(uint16_t status);
62 
63 #if defined(WRITE_IN_THREAD)
64  static void write_thread();
65  static volatile uint16_t rd_ptr;
66  static volatile uint16_t wr_ptr;
68  static void *_task;
69 #endif
70 
71 
72 #if defined(EEPROM_CACHED)
73  static uint8_t eeprom_buffer[BOARD_STORAGE_SIZE] IN_CCM;
74 #endif
75 };
76 
77 
static void * _task
Definition: Storage.h:68
static void do_on_disarm()
Definition: Storage.cpp:252
static uint8_t _read_byte(uint16_t loc)
Definition: Storage.cpp:145
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:161
#define BOARD_STORAGE_SIZE
Definition: board.h:134
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:221
static void _write_byte(uint16_t loc, uint8_t value)
Definition: Storage.cpp:202
static volatile uint16_t rd_ptr
Definition: Storage.h:65
static void error_parse(uint16_t status)
Definition: Storage.cpp:87
#define EEPROM_QUEUE_LEN
Definition: Storage.h:50
static uint8_t read_byte(uint16_t loc)
Definition: Storage.cpp:136
static void write_thread()
Definition: Storage.cpp:294
static Item queue[EEPROM_QUEUE_LEN]
Definition: Storage.h:67
static uint8_t eeprom_buffer [BOARD_STORAGE_SIZE] IN_CCM
Definition: Storage.h:73
static void write_byte(uint16_t loc, uint8_t value)
Definition: Storage.cpp:191
float value
static volatile uint16_t wr_ptr
Definition: Storage.h:66
static bool write_deferred
Definition: Storage.h:59
static void late_init(bool defer)
Definition: Storage.cpp:82
static void write_word(uint16_t loc, uint16_t value)
Definition: Storage.cpp:268