CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_FlashStorage/examples/FlashTest/FlashTest.cpp
Views: 1800
1
//
2
// Unit tests for the AP_Math rotations code
3
//
4
5
#include <AP_HAL/AP_HAL.h>
6
#include <AP_Math/AP_Math.h>
7
#include <AP_FlashStorage/AP_FlashStorage.h>
8
#include <stdio.h>
9
#include <AP_HAL/utility/sparse-endian.h>
10
11
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
12
13
class FlashTest : public AP_HAL::HAL::Callbacks {
14
public:
15
// HAL::Callbacks implementation.
16
void setup() override;
17
void loop() override;
18
19
private:
20
static const uint32_t flash_sector_size = 32U * 1024U;
21
22
uint8_t mem_buffer[AP_FlashStorage::storage_size];
23
uint8_t mem_mirror[AP_FlashStorage::storage_size];
24
25
// flash buffer
26
uint8_t *flash[2];
27
28
bool flash_write(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length);
29
bool flash_read(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length);
30
bool flash_erase(uint8_t sector);
31
bool flash_erase_ok(void);
32
33
AP_FlashStorage storage{mem_buffer,
34
flash_sector_size,
35
FUNCTOR_BIND_MEMBER(&FlashTest::flash_write, bool, uint8_t, uint32_t, const uint8_t *, uint16_t),
36
FUNCTOR_BIND_MEMBER(&FlashTest::flash_read, bool, uint8_t, uint32_t, uint8_t *, uint16_t),
37
FUNCTOR_BIND_MEMBER(&FlashTest::flash_erase, bool, uint8_t),
38
FUNCTOR_BIND_MEMBER(&FlashTest::flash_erase_ok, bool)};
39
40
// write to storage and mem_mirror
41
void write(uint16_t offset, const uint8_t *data, uint16_t length);
42
43
bool erase_ok;
44
};
45
46
bool FlashTest::flash_write(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
47
{
48
if (sector > 1) {
49
AP_HAL::panic("FATAL: write to sector %u", (unsigned)sector);
50
}
51
if (offset + length > flash_sector_size) {
52
AP_HAL::panic("FATAL: write to sector %u at offset %u length %u",
53
(unsigned)sector,
54
(unsigned)offset,
55
(unsigned)length);
56
}
57
uint8_t *b = &flash[sector][offset];
58
if ((offset & 1) || (length & 1)) {
59
AP_HAL::panic("FATAL: invalid write at %u:%u len=%u",
60
(unsigned)sector,
61
(unsigned)offset,
62
(unsigned)length);
63
}
64
uint16_t len16 = length/2;
65
for (uint16_t i=0; i<len16; i++) {
66
const uint16_t v = le16toh_ptr(&data[i*2]);
67
uint16_t v2 = le16toh_ptr(&b[i*2]);
68
if (v & !v2) {
69
AP_HAL::panic("FATAL: invalid write16 at %u:%u 0x%04x 0x%04x",
70
(unsigned)sector,
71
unsigned(offset+i),
72
b[i],
73
data[i]);
74
}
75
#ifndef AP_FLASHSTORAGE_MULTI_WRITE
76
if (v != v2 && v != 0xFFFF && v2 != 0xFFFF) {
77
AP_HAL::panic("FATAL: invalid write16 at %u:%u 0x%04x 0x%04x",
78
(unsigned)sector,
79
unsigned(offset+i),
80
b[i],
81
data[i]);
82
}
83
#endif
84
v2 &= v;
85
put_le16_ptr(&b[i*2], v2);
86
}
87
return true;
88
}
89
90
bool FlashTest::flash_read(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
91
{
92
if (sector > 1) {
93
AP_HAL::panic("FATAL: read from sector %u", (unsigned)sector);
94
}
95
if (offset + length > flash_sector_size) {
96
AP_HAL::panic("FATAL: read from sector %u at offset %u length %u",
97
(unsigned)sector,
98
(unsigned)offset,
99
(unsigned)length);
100
}
101
memcpy(data, &flash[sector][offset], length);
102
return true;
103
}
104
105
bool FlashTest::flash_erase(uint8_t sector)
106
{
107
if (sector > 1) {
108
AP_HAL::panic("FATAL: erase sector %u", (unsigned)sector);
109
}
110
memset(&flash[sector][0], 0xFF, flash_sector_size);
111
return true;
112
}
113
114
bool FlashTest::flash_erase_ok(void)
115
{
116
return erase_ok;
117
}
118
119
void FlashTest::write(uint16_t offset, const uint8_t *data, uint16_t length)
120
{
121
memcpy(&mem_mirror[offset], data, length);
122
memcpy(&mem_buffer[offset], data, length);
123
if (!storage.write(offset, length)) {
124
if (erase_ok) {
125
printf("Failed to write at %u for %u\n", offset, length);
126
}
127
}
128
}
129
130
/*
131
* test flash storage
132
*/
133
void FlashTest::setup(void)
134
{
135
hal.console->printf("AP_FlashStorage test\n");
136
}
137
138
void FlashTest::loop(void)
139
{
140
flash[0] = (uint8_t *)malloc(flash_sector_size);
141
flash[1] = (uint8_t *)malloc(flash_sector_size);
142
flash_erase(0);
143
flash_erase(1);
144
145
if (!storage.init()) {
146
AP_HAL::panic("Failed first init()");
147
}
148
149
// fill with 10k random writes
150
for (uint32_t i=0; i<5000000; i++) {
151
uint16_t ofs = get_random16() % sizeof(mem_buffer);
152
uint16_t length = get_random16() & 0x1F;
153
length = MIN(length, sizeof(mem_buffer) - ofs);
154
uint8_t data[length];
155
for (uint8_t j=0; j<length; j++) {
156
data[j] = get_random16() & 0xFF;
157
}
158
159
erase_ok = (i % 1000 == 0);
160
write(ofs, data, length);
161
162
if (erase_ok) {
163
if (memcmp(mem_buffer, mem_mirror, sizeof(mem_buffer)) != 0) {
164
AP_HAL::panic("FATAL: data mis-match at i=%u", (unsigned)i);
165
}
166
}
167
}
168
169
// force final write to allow for flush with erase_ok
170
erase_ok = true;
171
uint8_t b = 42;
172
write(37, &b, 1);
173
174
if (memcmp(mem_buffer, mem_mirror, sizeof(mem_buffer)) != 0) {
175
AP_HAL::panic("FATAL: data mis-match before re-init");
176
}
177
178
// re-init
179
printf("re-init\n");
180
memset(mem_buffer, 0, sizeof(mem_buffer));
181
if (!storage.init()) {
182
AP_HAL::panic("Failed second init()");
183
}
184
185
if (memcmp(mem_buffer, mem_mirror, sizeof(mem_buffer)) != 0) {
186
AP_HAL::panic("FATAL: data mis-match");
187
}
188
while (true) {
189
hal.console->printf("TEST PASSED");
190
hal.scheduler->delay(20000);
191
}
192
}
193
194
FlashTest flashtest;
195
196
AP_HAL_MAIN_CALLBACKS(&flashtest);
197
198