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/Tools/AP_Bootloader/flash_from_sd.cpp
Views: 1798
1
#include "flash_from_sd.h"
2
3
#if AP_BOOTLOADER_FLASH_FROM_SD_ENABLED
4
5
#include "ch.h"
6
#include "ff.h"
7
8
#include "md5.h"
9
10
#include <string.h>
11
#include <stdint.h>
12
#include <stdio.h>
13
#include <fcntl.h>
14
#include "stm32_util.h"
15
16
#include <AP_HAL_ChibiOS/hwdef/common/flash.h>
17
#include <AP_Math/AP_Math.h>
18
#include "support.h"
19
20
// swiped from support.cpp:
21
static const uint8_t *flash_base = (const uint8_t *)(0x08000000 + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U);
22
23
24
// taken from AP_Common.cpp as we don't want to compile the AP_Common
25
// directory. This function is defined in AP_Common.h - so we can't
26
// use "static" here.
27
/**
28
* return the numeric value of an ascii hex character
29
*
30
* @param[in] a Hexadecimal character
31
* @return Returns a binary value
32
*/
33
uint8_t char_to_hex(char a)
34
{
35
if (a >= 'A' && a <= 'F')
36
return a - 'A' + 10;
37
else if (a >= 'a' && a <= 'f')
38
return a - 'a' + 10;
39
else
40
return a - '0';
41
}
42
43
#define MAX_IO_SIZE 4096
44
static uint8_t buffer[MAX_IO_SIZE];
45
46
// a class which provides parsing functionality for abin files;
47
// inheritors must supply a function to deal with the body of the abin
48
// and may supply methods run() (to initialise their state) and
49
// name_value_callback (to handle name/value pairs extracted from the
50
// abin header.
51
class ABinParser {
52
public:
53
ABinParser(const char *_path) :
54
path{_path}
55
{ }
56
virtual ~ABinParser() {}
57
58
virtual bool run() = 0;
59
60
protected:
61
62
virtual void name_value_callback(const char *name, const char *value) {}
63
virtual void body_callback(const uint8_t *bytes, uint32_t n) = 0;
64
bool parse();
65
66
private:
67
68
const char *path;
69
70
};
71
72
bool ABinParser::parse()
73
{
74
FIL fh;
75
if (f_open(&fh, path, FA_READ) != FR_OK) {
76
return false;
77
}
78
enum class State {
79
START_NAME=17, // "MD5: "
80
ACCUMULATING_NAME=19,
81
ACCUMULATING_VALUE = 30,
82
START_BODY = 40,
83
PROCESSING_BODY = 45,
84
SKIPPING_POST_COLON_SPACES = 50,
85
START_VALUE = 55,
86
};
87
88
State state = State::START_NAME;
89
uint16_t name_start = 0;
90
uint16_t name_end = 0;
91
uint16_t value_start = 0;
92
// for efficiency we assume all headers are within the first chunk
93
// read i.e. the name/value pairs do not cross a MAX_IO_SIZE
94
// boundary
95
while (true) {
96
UINT bytes_read;
97
if (f_read(&fh, buffer, sizeof(buffer), &bytes_read) != FR_OK) {
98
return false;
99
}
100
if (bytes_read > sizeof(buffer)) {
101
// error
102
return false;
103
}
104
if (bytes_read == 0) {
105
break;
106
}
107
for (uint16_t i=0; i<bytes_read; i++) {
108
switch (state) {
109
case State::START_NAME: {
110
// check for delimiter:
111
if (bytes_read-i >= 3) {
112
if (!strncmp((char*)&buffer[i], "--\n", bytes_read-i)) {
113
// end of headers
114
i += 2;
115
state = State::START_BODY;
116
continue;
117
}
118
}
119
// sanity check input:
120
if (buffer[i] == ':') {
121
// zero-length name?! just say no:
122
return false;
123
}
124
if (buffer[i] == '\n') {
125
// empty line... ignore it
126
continue;
127
}
128
name_start = i;
129
state = State::ACCUMULATING_NAME;
130
continue;
131
}
132
case State::ACCUMULATING_NAME: {
133
if (buffer[i] == '\n') {
134
// no colon on this line; just say no:
135
return false;
136
}
137
if (buffer[i] == ':') {
138
name_end = i;
139
state = State::SKIPPING_POST_COLON_SPACES;
140
continue;
141
}
142
// continue to accumulate name
143
continue;
144
}
145
case State::SKIPPING_POST_COLON_SPACES:
146
if (buffer[i] == ' ') {
147
// continue to accumulate spaces
148
continue;
149
}
150
state = State::START_VALUE;
151
FALLTHROUGH;
152
case State::START_VALUE:
153
value_start = i;
154
state = State::ACCUMULATING_VALUE;
155
FALLTHROUGH;
156
case State::ACCUMULATING_VALUE: {
157
if (buffer[i] != '\n') {
158
// continue to accumate value bytes
159
continue;
160
}
161
char name[80];
162
char value[80];
163
strncpy(name, (char*)&buffer[name_start], MIN(sizeof(name)-1, name_end-name_start));
164
strncpy(value, (char*)&buffer[value_start], MIN(sizeof(value)-1, i-value_start));
165
name_value_callback(name, value);
166
state = State::START_NAME;
167
continue;
168
}
169
case State::START_BODY:
170
state = State::PROCESSING_BODY;
171
FALLTHROUGH;
172
case State::PROCESSING_BODY:
173
body_callback(&buffer[i], bytes_read-i);
174
i = bytes_read;
175
continue;
176
}
177
}
178
}
179
180
// successfully parsed the abin. Call the body callback once more
181
// with zero bytes indicating EOF:
182
body_callback((uint8_t*)"", 0);
183
184
return true;
185
}
186
187
// a sub-class of ABinParser which takes the supplied MD5 from the
188
// abin header and compares it against the calculated md5sum of the
189
// abin body
190
class ABinVerifier : ABinParser {
191
public:
192
193
using ABinParser::ABinParser;
194
195
bool run() override {
196
MD5Init(&md5_context);
197
198
if (!parse()) {
199
return false;
200
}
201
202
// verify the checksum is as expected
203
uint8_t calculated_md5[16];
204
MD5Final(calculated_md5, &md5_context);
205
if (!memcmp(calculated_md5, expected_md5, sizeof(calculated_md5))) {
206
// checksums match
207
return true;
208
}
209
210
return false;
211
}
212
213
protected:
214
215
void name_value_callback(const char *name, const char *value) override {
216
if (strncmp(name, "MD5", 3)) {
217
// only interested in MD5 header
218
return;
219
}
220
221
// convert from 32-byte-string to 16-byte number:
222
for (uint8_t j=0; j<16; j++) {
223
expected_md5[j] = (char_to_hex(value[j*2]) << 4) | char_to_hex(value[j*2+1]);
224
}
225
}
226
227
void body_callback(const uint8_t *bytes, uint32_t nbytes) override {
228
MD5Update(&md5_context, bytes, nbytes);
229
}
230
231
private:
232
233
uint8_t expected_md5[16];
234
MD5Context md5_context;
235
};
236
237
238
// a sub-class of ABinParser which flashes the body of the supplied abin
239
class ABinFlasher : public ABinParser {
240
public:
241
using ABinParser::ABinParser;
242
243
bool run() override {
244
// start by erasing all sectors
245
for (uint8_t i = 0; flash_func_sector_size(i) != 0; i++) {
246
if (!flash_func_erase_sector(i)) {
247
return false;
248
}
249
led_toggle(LED_BOOTLOADER);
250
}
251
252
// parse and flash
253
if (!parse()) {
254
return false;
255
}
256
257
return !failed;
258
}
259
260
protected:
261
262
void body_callback(const uint8_t *bytes, uint32_t nbytes) override {
263
if (failed) {
264
return;
265
}
266
267
memcpy(&buffer[buffer_ofs], bytes, nbytes);
268
buffer_ofs += nbytes;
269
270
const uint32_t WRITE_CHUNK_SIZE = 32*1024; // must be less than size of state buffer
271
// nbytes is zero after the last chunk in the body
272
if (buffer_ofs > WRITE_CHUNK_SIZE || nbytes == 0) {
273
uint32_t write_size = WRITE_CHUNK_SIZE;
274
uint32_t padded_write_size = write_size;
275
if (nbytes == 0) {
276
// final chunk. We have to align to 128 bytes
277
write_size = buffer_ofs;
278
padded_write_size = write_size;
279
const uint8_t pad_size = 128 - (write_size % 128);
280
// zero those extra bytes:
281
memset(&buffer[buffer_ofs], '\0', pad_size);
282
padded_write_size += pad_size;
283
}
284
const uint32_t ofs = uint32_t(flash_base) + flash_ofs;
285
if (!stm32_flash_write(ofs, buffer, padded_write_size)) {
286
failed = true;
287
return;
288
}
289
flash_ofs += padded_write_size;
290
buffer_ofs -= write_size;
291
memcpy(buffer, &buffer[write_size], buffer_ofs);
292
led_toggle(LED_BOOTLOADER);
293
}
294
}
295
296
private:
297
298
uint32_t flash_ofs = 0;
299
uint32_t buffer_ofs = 0;
300
uint8_t buffer[64*1024]; // constrained by memory map on bootloader
301
bool failed = false;
302
};
303
304
305
// main entry point to the flash-from-sd-card functionality; called
306
// from the bootloader main function
307
bool flash_from_sd()
308
{
309
peripheral_power_enable();
310
311
if (!sdcard_init()) {
312
return false;
313
}
314
315
bool ret = false;
316
317
// expected filepath for abin:
318
const char *abin_path = "/ardupilot.abin";
319
// we rename to this before verifying the abin:
320
const char *verify_abin_path = "/ardupilot-verify.abin";
321
// we rename to this before flashing the abin:
322
const char *flash_abin_path = "/ardupilot-flash.abin";
323
// we rename to this after flashing the abin:
324
const char *flashed_abin_path = "/ardupilot-flashed.abin";
325
326
ABinVerifier *verifier = nullptr;
327
ABinFlasher *flasher = nullptr;
328
329
FILINFO info;
330
if (f_stat(abin_path, &info) != FR_OK) {
331
goto out;
332
}
333
334
f_unlink(verify_abin_path);
335
f_unlink(flash_abin_path);
336
f_unlink(flashed_abin_path);
337
338
// rename the file so we only ever attempt to flash from it once:
339
if (f_rename(abin_path, verify_abin_path) != FR_OK) {
340
// we would be nice to indicate an error here.
341
// we could try to drop a message on the SD card?
342
return false;
343
}
344
345
verifier = NEW_NOTHROW ABinVerifier{verify_abin_path};
346
if (!verifier->run()) {
347
goto out;
348
}
349
350
// rename the file so we only ever attempt to flash from it once:
351
if (f_rename(verify_abin_path, flash_abin_path) != FR_OK) {
352
// we would be nice to indicate an error here.
353
// we could try to drop a message on the SD card?
354
return false;
355
}
356
357
flasher = NEW_NOTHROW ABinFlasher{flash_abin_path};
358
if (!flasher->run()) {
359
goto out;
360
}
361
362
// rename the file to indicate successful flash:
363
if (f_rename(flash_abin_path, flashed_abin_path) != FR_OK) {
364
// we would be nice to indicate an error here.
365
// we could try to drop a message on the SD card?
366
return false;
367
}
368
369
ret = true;
370
371
out:
372
373
delete verifier;
374
verifier = nullptr;
375
376
delete flasher;
377
flasher = nullptr;
378
379
sdcard_stop();
380
// should we disable peripheral power again?!
381
382
return ret;
383
}
384
385
#endif // AP_BOOTLOADER_FLASH_FROM_SD_ENABLED
386
387