APM:Libraries
Storage.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
3 
4 #include <assert.h>
5 #include <sys/types.h>
6 #include <sys/stat.h>
7 #include <fcntl.h>
8 #include <unistd.h>
9 #include <errno.h>
10 #include <stdio.h>
11 #include <ctype.h>
12 #include <nuttx/progmem.h>
13 
15 
16 #include "Storage.h"
17 using namespace PX4;
18 
19 /*
20  This stores eeprom data in the PX4 MTD interface with a 4k size, and
21  a in-memory buffer. This keeps the latency and devices IOs down.
22 */
23 
24 // name the storage file after the sketch so you can use the same sd
25 // card for ArduCopter and ArduPlane
26 #define STORAGE_DIR "/fs/microsd/APM"
27 //#define SAVE_STORAGE_FILE STORAGE_DIR "/" SKETCHNAME ".sav"
28 #define MTD_PARAMS_FILE "/fs/mtd"
29 
30 extern const AP_HAL::HAL& hal;
31 
32 extern "C" int mtd_main(int, char **);
33 
35  _perf_storage(perf_alloc(PC_ELAPSED, "APM_storage")),
36  _perf_errors(perf_alloc(PC_COUNT, "APM_storage_errors"))
37 {
38 }
39 
41 {
42  if (_initialised) {
43  return;
44  }
45 
47 
48  // load from storage backend
49 #if USE_FLASH_STORAGE
50  _flash_load();
51 #else
52  _mtd_load();
53 #endif
54 
55 #ifdef SAVE_STORAGE_FILE
56  fd = open(SAVE_STORAGE_FILE, O_WRONLY|O_CREAT|O_TRUNC, 0644);
57  if (fd != -1) {
58  write(fd, _buffer, sizeof(_buffer));
59  close(fd);
60  ::printf("Saved storage file %s\n", SAVE_STORAGE_FILE);
61  }
62 #endif
63  _initialised = true;
64 }
65 
66 /*
67  mark some lines as dirty. Note that there is no attempt to avoid
68  the race condition between this code and the _timer_tick() code
69  below, which both update _dirty_mask. If we lose the race then the
70  result is that a line is written more than once, but it won't result
71  in a line not being written.
72 */
73 void PX4Storage::_mark_dirty(uint16_t loc, uint16_t length)
74 {
75  uint16_t end = loc + length;
76  for (uint16_t line=loc>>PX4_STORAGE_LINE_SHIFT;
77  line <= end>>PX4_STORAGE_LINE_SHIFT;
78  line++) {
79  _dirty_mask.set(line);
80  }
81 }
82 
83 void PX4Storage::read_block(void *dst, uint16_t loc, size_t n)
84 {
85  if (loc >= sizeof(_buffer)-(n-1)) {
86  return;
87  }
88  _storage_open();
89  memcpy(dst, &_buffer[loc], n);
90 }
91 
92 void PX4Storage::write_block(uint16_t loc, const void *src, size_t n)
93 {
94  if (loc >= sizeof(_buffer)-(n-1)) {
95  return;
96  }
97  if (memcmp(src, &_buffer[loc], n) != 0) {
98  _storage_open();
99  memcpy(&_buffer[loc], src, n);
100  _mark_dirty(loc, n);
101  }
102 }
103 
105 {
106  if (!_initialised || _dirty_mask.empty()) {
107  return;
108  }
109  perf_begin(_perf_storage);
110 
111 #if !USE_FLASH_STORAGE
112  if (_fd == -1) {
113  _fd = open(MTD_PARAMS_FILE, O_WRONLY);
114  if (_fd == -1) {
115  perf_end(_perf_storage);
116  perf_count(_perf_errors);
117  return;
118  }
119  }
120 #endif
121 
122  // write out the first dirty line. We don't write more
123  // than one to keep the latency of this call to a minimum
124  uint16_t i;
125  for (i=0; i<PX4_STORAGE_NUM_LINES; i++) {
126  if (_dirty_mask.get(i)) {
127  break;
128  }
129  }
130  if (i == PX4_STORAGE_NUM_LINES) {
131  // this shouldn't be possible
132  perf_end(_perf_storage);
133  perf_count(_perf_errors);
134  return;
135  }
136 
137  // save to storage backend
138 #if USE_FLASH_STORAGE
139  _flash_write(i);
140 #else
141  _mtd_write(i);
142 #endif
143 
144  perf_end(_perf_storage);
145 }
146 
147 #if !USE_FLASH_STORAGE
148 void PX4Storage::bus_lock(bool lock)
149 {
150 #if defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
151  /*
152  this is needed on Pixracer where the ms5611 may be on the same
153  bus as FRAM, and the NuttX ramtron driver does not go via the
154  PX4 spi bus abstraction. The ramtron driver relies on
155  SPI_LOCK(). We need to prevent the ms5611 reads which happen in
156  interrupt context from interfering with the FRAM operations. As
157  the px4 spi bus abstraction just uses interrupt blocking as the
158  locking mechanism we need to block interrupts here as well.
159  */
160  if (lock) {
161  irq_state = irqsave();
162  } else {
163  irqrestore(irq_state);
164  }
165 #endif
166 }
167 
168 
169 /*
170  write one storage line. This also updates _dirty_mask.
171 */
172 void PX4Storage::_mtd_write(uint16_t line)
173 {
174  uint16_t ofs = line * PX4_STORAGE_LINE_SIZE;
175  if (lseek(_fd, ofs, SEEK_SET) != ofs) {
176  return;
177  }
178 
179  // mark the line clean
180  _dirty_mask.clear(line);
181 
182  bus_lock(true);
183  ssize_t ret = write(_fd, &_buffer[ofs], PX4_STORAGE_LINE_SIZE);
184  bus_lock(false);
185 
186  if (ret != PX4_STORAGE_LINE_SIZE) {
187  // write error - likely EINTR
188  _dirty_mask.set(line);
189  close(_fd);
190  _fd = -1;
191  perf_count(_perf_errors);
192  }
193 }
194 
195 /*
196  load all data from mtd
197  */
199 {
201  printf("mtd: started OK\n");
202  if (AP_BoardConfig::px4_start_driver(mtd_main, "mtd", "readtest " MTD_PARAMS_FILE)) {
203  printf("mtd: readtest OK\n");
204  } else {
205  AP_BoardConfig::sensor_config_error("mtd: failed readtest");
206  }
207  } else {
208  AP_BoardConfig::sensor_config_error("mtd: failed start");
209  }
210 
211  int fd = open(MTD_PARAMS_FILE, O_RDONLY);
212  if (fd == -1) {
213  AP_HAL::panic("Failed to open " MTD_PARAMS_FILE);
214  }
215  const uint16_t chunk_size = 128;
216  for (uint16_t ofs=0; ofs<sizeof(_buffer); ofs += chunk_size) {
217  bus_lock(true);
218  ssize_t ret = read(fd, &_buffer[ofs], chunk_size);
219  bus_lock(false);
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);
223  AP_HAL::panic("Failed to read " MTD_PARAMS_FILE);
224  }
225  }
226  close(fd);
227 }
228 
229 #else // USE_FLASH_STORAGE
230 
231 /*
232  load all data from flash
233  */
234 void PX4Storage::_flash_load(void)
235 {
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) {
239  AP_HAL::panic("Bad flash page sizes %u %u",
240  up_progmem_pagesize(_flash_page),
241  up_progmem_pagesize(_flash_page+1));
242  }
243 
244  printf("Storage: Using flash pages %u and %u\n", _flash_page, _flash_page+1);
245 
246  if (!_flash.init()) {
247  AP_HAL::panic("unable to init flash storage");
248  }
249 }
250 
251 /*
252  write one storage line. This also updates _dirty_mask.
253 */
254 void PX4Storage::_flash_write(uint16_t line)
255 {
256  if (_flash.write(line*PX4_STORAGE_LINE_SIZE, PX4_STORAGE_LINE_SIZE)) {
257  // mark the line clean
258  _dirty_mask.clear(line);
259  } else {
260  perf_count(_perf_errors);
261  }
262 }
263 
264 /*
265  callback to write data to flash
266  */
267 bool PX4Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
268 {
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()) {
272  // we are getting flash write errors while disarmed. Try
273  // re-writing all of flash
274  uint32_t now = AP_HAL::millis();
275  if (now - _last_re_init_ms > 5000) {
276  _last_re_init_ms = now;
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);
280  }
281  }
282  return ret;
283 }
284 
285 /*
286  callback to read data from flash
287  */
288 bool PX4Storage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
289 {
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);
293  return true;
294 }
295 
296 /*
297  callback to erase flash sector
298  */
299 bool PX4Storage::_flash_erase_sector(uint8_t sector)
300 {
301  return up_progmem_erasepage(_flash_page+sector) > 0;
302 }
303 
304 /*
305  callback to check if erase is allowed
306  */
307 bool PX4Storage::_flash_erase_ok(void)
308 {
309  // only allow erase while disarmed
310  return !hal.util->get_soft_armed();
311 }
312 #endif // USE_FLASH_STORAGE
313 
314 
315 #endif // CONFIG_HAL_BOARD
perf_counter_t _perf_storage
Definition: Storage.h:47
int printf(const char *fmt,...)
Definition: stdio.c:113
bool get_soft_armed() const
Definition: Util.h:15
void bus_lock(bool lock)
Definition: Storage.cpp:148
volatile bool _initialised
Definition: Storage.h:41
#define PX4_STORAGE_LINE_SIZE
Definition: Storage.h:27
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:92
void _mtd_load(void)
Definition: Storage.cpp:198
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:83
void clear(uint16_t bit)
Definition: Bitmask.h:56
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
AP_HAL::Util * util
Definition: HAL.h:115
bool empty(void) const
Definition: Bitmask.h:75
#define PX4_STORAGE_LINE_SHIFT
Definition: Storage.h:24
void _storage_open(void)
Definition: Storage.cpp:40
Bitmask _dirty_mask
Definition: Storage.h:46
int mtd_main(int, char **)
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
bool get(uint16_t bit) const
Definition: Bitmask.h:68
void _timer_tick(void) override
Definition: Storage.cpp:104
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments)
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
Definition: posix.c:612
uint32_t _last_re_init_ms
Definition: Storage.h:49
perf_counter_t _perf_errors
Definition: Storage.h:48
void _mark_dirty(uint16_t loc, uint16_t length)
Definition: Storage.cpp:73
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
void set(uint16_t bit)
Definition: Bitmask.h:34
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define MTD_PARAMS_FILE
Definition: Storage.cpp:28
void clearall(void)
Definition: Bitmask.h:63
void _mtd_write(uint16_t line)
Definition: Storage.cpp:172
#define PX4_STORAGE_NUM_LINES
Definition: Storage.h:28
static const AP_HAL::HAL & hal
Definition: Device.cpp:29
static void sensor_config_error(const char *reason)