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/AP_FlashStorage.h
Views: 1798
1
/*
2
Please contribute your ideas! See https://ardupilot.org/dev for details
3
4
This program is free software: you can redistribute it and/or modify
5
it under the terms of the GNU General Public License as published by
6
the Free Software Foundation, either version 3 of the License, or
7
(at your option) any later version.
8
9
This program is distributed in the hope that it will be useful,
10
but WITHOUT ANY WARRANTY; without even the implied warranty of
11
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12
GNU General Public License for more details.
13
14
You should have received a copy of the GNU General Public License
15
along with this program. If not, see <http://www.gnu.org/licenses/>.
16
*/
17
/*
18
a class to allow for FLASH to be used as a memory backed storage
19
backend for any HAL. The basic methodology is to use a log based
20
storage system over two flash sectors. Key design elements:
21
22
- erase of sectors only called on init, as erase will lock the flash
23
and prevent code execution
24
25
- write using log based system
26
27
- read requires scan of all log elements. This is expected to be called rarely
28
29
- assumes flash that erases to 0xFF and where writing can only clear
30
bits, not set them
31
32
- assumes flash sectors are much bigger than storage size. If they
33
aren't then caller can aggregate multiple sectors. Designed for
34
128k flash sectors with 16k storage size.
35
36
- assumes two flash sectors are available
37
*/
38
#pragma once
39
40
#include <AP_HAL/AP_HAL.h>
41
42
/*
43
we support 3 different types of flash which have different restrictions
44
*/
45
#define AP_FLASHSTORAGE_TYPE_F1 1 // F1 and F3
46
#define AP_FLASHSTORAGE_TYPE_F4 2 // F4 and F7
47
#define AP_FLASHSTORAGE_TYPE_H7 3 // H7
48
#define AP_FLASHSTORAGE_TYPE_G4 4 // G4
49
50
#ifndef AP_FLASHSTORAGE_TYPE
51
#if defined(STM32F1) || defined(STM32F3)
52
/*
53
the STM32F1 and STM32F3 can't change individual bits from 1 to 0
54
unless all bits in the 16 bit word are 1
55
*/
56
#define AP_FLASHSTORAGE_TYPE AP_FLASHSTORAGE_TYPE_F1
57
#elif defined(STM32H7)
58
/*
59
STM32H7 can only write in 32 byte chunks, and must only write when all bits are 1
60
*/
61
#define AP_FLASHSTORAGE_TYPE AP_FLASHSTORAGE_TYPE_H7
62
#elif defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
63
/*
64
STM32G4 can only write in 8 byte chunks, and must only write when all bits are 1
65
*/
66
#define AP_FLASHSTORAGE_TYPE AP_FLASHSTORAGE_TYPE_G4
67
#else // F4, F7
68
/*
69
STM32HF4 and STM32H7 can update bits from 1 to 0
70
*/
71
#define AP_FLASHSTORAGE_TYPE AP_FLASHSTORAGE_TYPE_F4
72
#endif
73
#endif
74
75
/*
76
The StorageManager holds the layout of non-volatile storage
77
*/
78
class AP_FlashStorage {
79
private:
80
#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7
81
// need to write in 32 byte chunks, with 2 byte header
82
static const uint8_t block_size = 30;
83
static const uint8_t max_write = block_size;
84
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4
85
// write in 8 byte chunks, with 2 byte header
86
static const uint8_t block_size = 6;
87
static const uint8_t max_write = block_size;
88
#else
89
static const uint8_t block_size = 8;
90
static const uint8_t max_write = 64;
91
#endif
92
static const uint16_t num_blocks = (HAL_STORAGE_SIZE+(block_size-1)) / block_size;
93
94
public:
95
// caller provided function to write to a flash sector
96
FUNCTOR_TYPEDEF(FlashWrite, bool, uint8_t , uint32_t , const uint8_t *, uint16_t );
97
98
// caller provided function to read from a flash sector. Only called on init()
99
FUNCTOR_TYPEDEF(FlashRead, bool, uint8_t , uint32_t , uint8_t *, uint16_t );
100
101
// caller provided function to erase a flash sector. Only called from init()
102
FUNCTOR_TYPEDEF(FlashErase, bool, uint8_t );
103
104
// caller provided function to indicate if erasing is allowed
105
FUNCTOR_TYPEDEF(FlashEraseOK, bool);
106
107
// constructor.
108
AP_FlashStorage(uint8_t *mem_buffer, // buffer of storage_size bytes
109
uint32_t flash_sector_size, // size of each flash sector in bytes
110
FlashWrite flash_write, // function to write to flash
111
FlashRead flash_read, // function to read from flash
112
FlashErase flash_erase, // function to erase flash
113
FlashEraseOK flash_erase_ok); // function to check if erasing allowed
114
115
// initialise storage, filling mem_buffer with current contents
116
bool init(void);
117
118
// erase sectors and re-initialise
119
bool erase(void) WARN_IF_UNUSED {
120
return erase_all();
121
}
122
123
// re-initialise storage, using current mem_buffer
124
bool re_initialise(void) WARN_IF_UNUSED;
125
126
// switch full sector - should only be called when safe to have CPU
127
// offline for considerable periods as an erase will be needed
128
bool switch_full_sector(void) WARN_IF_UNUSED;
129
130
// write some data to storage from mem_buffer
131
bool write(uint16_t offset, uint16_t length) WARN_IF_UNUSED;
132
133
// fixed storage size
134
static const uint16_t storage_size = HAL_STORAGE_SIZE;
135
136
private:
137
uint8_t *mem_buffer;
138
const uint32_t flash_sector_size;
139
FlashWrite flash_write;
140
FlashRead flash_read;
141
FlashErase flash_erase;
142
FlashEraseOK flash_erase_ok;
143
144
uint8_t current_sector;
145
uint32_t write_offset;
146
uint32_t reserved_space;
147
bool write_error;
148
149
// 24 bit signature
150
#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F4
151
static const uint32_t signature = 0x51685B;
152
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F1
153
static const uint32_t signature = 0x51;
154
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7
155
static const uint32_t signature = 0x51685B62;
156
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4
157
static const uint32_t signature = 0x1586B562;
158
#else
159
#error "Unknown AP_FLASHSTORAGE_TYPE"
160
#endif
161
162
// sector states, representation depends on storage type
163
enum SectorState {
164
SECTOR_STATE_AVAILABLE = 1,
165
SECTOR_STATE_IN_USE = 2,
166
SECTOR_STATE_FULL = 3,
167
SECTOR_STATE_INVALID = 4
168
};
169
170
// header in first word of each sector
171
struct sector_header {
172
#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F4
173
uint32_t state1:8;
174
uint32_t signature1:24;
175
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F1
176
uint32_t state1:32;
177
uint32_t signature1:16;
178
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7
179
// needs to be 96 bytes on H7 to support 3 states
180
uint32_t state1;
181
uint32_t signature1;
182
uint32_t pad1[6];
183
uint32_t state2;
184
uint32_t signature2;
185
uint32_t pad2[6];
186
uint32_t state3;
187
uint32_t signature3;
188
uint32_t pad3[6];
189
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4
190
// needs to be 24 bytes on G4 to support 3 states
191
uint32_t state1;
192
uint32_t signature1;
193
uint32_t state2;
194
uint32_t signature2;
195
uint32_t state3;
196
uint32_t signature3;
197
#endif
198
bool signature_ok(void) const;
199
SectorState get_state() const;
200
void set_state(SectorState state);
201
};
202
203
204
enum BlockState {
205
BLOCK_STATE_AVAILABLE = 0x3,
206
BLOCK_STATE_WRITING = 0x1,
207
BLOCK_STATE_VALID = 0x0
208
};
209
210
// header of each block of data
211
struct block_header {
212
uint16_t state:2;
213
uint16_t block_num:11;
214
uint16_t num_blocks_minus_one:3;
215
};
216
217
// amount of space needed to write full storage
218
static const uint32_t reserve_size = (storage_size / max_write) * (sizeof(block_header) + max_write) + max_write;
219
220
// load data from a sector
221
bool load_sector(uint8_t sector) WARN_IF_UNUSED;
222
223
// erase a sector and write header
224
bool erase_sector(uint8_t sector, bool mark_available) WARN_IF_UNUSED;
225
226
// erase all sectors and reset
227
bool erase_all() WARN_IF_UNUSED;
228
229
// write all of mem_buffer to current sector
230
bool write_all() WARN_IF_UNUSED;
231
232
// return true if all bytes are zero
233
bool all_zero(uint16_t ofs, uint16_t size) WARN_IF_UNUSED;
234
235
// switch to next sector for writing
236
bool switch_sectors(void) WARN_IF_UNUSED;
237
238
// _switch_full_sector is protected by switch_full_sector to avoid
239
// an infinite recursion problem; switch_full_sector calls
240
// write() which can call switch_full_sector. This has been seen
241
// in practice.
242
bool protected_switch_full_sector(void) WARN_IF_UNUSED;
243
bool in_switch_full_sector;
244
};
245
246