APM:Libraries
StorageTest.cpp
Go to the documentation of this file.
1 //
2 // Simple test for the StorageManager class
3 //
4 
5 #include <AP_HAL/AP_HAL.h>
7 
8 void setup();
9 void loop();
10 
12 
13 #define DO_INITIALISATION 1
14 
15 /*
16  instantiate all 4 storage types
17  */
18 static StorageAccess all_storage[4] = {
23 };
24 
25 /*
26  simple random generator, see http://en.wikipedia.org/wiki/Random_number_generation
27  */
28 static uint16_t get_random(void)
29 {
30  static uint32_t m_z = 1234;
31  static uint32_t m_w = 76542;
32  m_z = 36969 * (m_z & 65535) + (m_z >> 16);
33  m_w = 18000 * (m_w & 65535) + (m_w >> 16);
34  return ((m_z << 16) + m_w) & 0xFFFF;
35 }
36 
37 /*
38  return a predictable value for an offset
39  */
40 static uint8_t pvalue(uint16_t offset)
41 {
42  return ((offset * 7) + 13) % 65536;
43 }
44 
45 void setup(void)
46 {
47  hal.console->printf("StorageTest startup...\n");
48 #if DO_INITIALISATION
49  for (uint8_t type = 0; type < 4; type++) {
50  const StorageAccess &storage = all_storage[type];
51  hal.console->printf("Init type %u\n", (unsigned)type);
52  for (uint16_t i = 0; i < storage.size(); i++) {
53  storage.write_byte(i, pvalue(i));
54  }
55  }
56 #endif
57 }
58 
59 void loop(void)
60 {
61  static uint32_t count;
62  uint8_t type = get_random() % 4;
63  const StorageAccess &storage = all_storage[type];
64  uint16_t offset = get_random() % storage.size();
65  uint8_t length = (get_random() & 31);
66  if (offset + length > storage.size()) {
67  length = storage.size() - offset;
68  }
69  if (length == 0) {
70  return;
71  }
72  uint8_t b[length];
73  for (uint8_t i=0; i<length; i++) {
74  b[i] = pvalue(offset+i);
75  }
76 
77  if (get_random() % 2 == 1) {
78  if (!storage.write_block(offset, b, length)) {
79  hal.console->printf("write failed at offset %u length %u\n",
80  (unsigned)offset, (unsigned)length);
81  }
82  } else {
83  uint8_t b2[length];
84  if (!storage.read_block(b2, offset, length)) {
85  hal.console->printf("read failed at offset %u length %u\n",
86  (unsigned)offset, (unsigned)length);
87  }
88  if (memcmp(b, b2, length) != 0) {
89  hal.console->printf("bad data at offset %u length %u\n",
90  (unsigned)offset, (unsigned)length);
91  }
92  }
93 
94  count++;
95  if (count % 10000 == 0) {
96  hal.console->printf("%u ops\n", (unsigned)count);
97  }
98 }
99 
100 
101 
102 AP_HAL_MAIN();
void setup()
Definition: StorageTest.cpp:45
AP_HAL_MAIN()
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static uint16_t get_random(void)
Definition: StorageTest.cpp:28
uint16_t size(void) const
void write_byte(uint16_t loc, uint8_t value) const
void loop()
Definition: StorageTest.cpp:59
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool read_block(void *dst, uint16_t src, size_t n) const
const HAL & get_HAL()
static uint8_t pvalue(uint16_t offset)
Definition: StorageTest.cpp:40
bool write_block(uint16_t dst, const void *src, size_t n) const
static StorageAccess all_storage[4]
Definition: StorageTest.cpp:18
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: StorageTest.cpp:11