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/support.cpp
Views: 1798
1
/*
2
bootloader support functions
3
*/
4
5
#include <AP_HAL/AP_HAL.h>
6
#include "ch.h"
7
#include "hal.h"
8
#include "hwdef.h"
9
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
10
#include <AP_HAL_ChibiOS/hwdef/common/flash.h>
11
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
12
#include <AP_Math/AP_Math.h>
13
#include "support.h"
14
#include "mcu_f1.h"
15
#include "mcu_f3.h"
16
#include "mcu_f4.h"
17
#include "mcu_f7.h"
18
#include "mcu_h7.h"
19
#include "mcu_g4.h"
20
#include "mcu_l4.h"
21
22
// optional uprintf() code for debug
23
// #define BOOTLOADER_DEBUG SD1
24
25
#ifndef AP_BOOTLOADER_ALWAYS_ERASE
26
#define AP_BOOTLOADER_ALWAYS_ERASE 0
27
#endif
28
29
#if defined(BOOTLOADER_DEV_LIST)
30
static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST };
31
#if HAL_USE_SERIAL == TRUE
32
static SerialConfig sercfg;
33
#endif
34
static int8_t locked_uart = -1;
35
static uint8_t last_uart;
36
37
#ifndef BOOTLOADER_BAUDRATE
38
#define BOOTLOADER_BAUDRATE 115200
39
#endif
40
41
// #pragma GCC optimize("O0")
42
43
static bool cin_data(uint8_t *data, uint8_t len, unsigned timeout_ms)
44
{
45
for (uint8_t i=0; i<ARRAY_SIZE(uarts); i++) {
46
if (locked_uart == -1 || locked_uart == i) {
47
if (chnReadTimeout(uarts[i], data, len, chTimeMS2I(timeout_ms)) == len) {
48
last_uart = i;
49
return true;
50
}
51
}
52
}
53
chThdSleepMicroseconds(500);
54
return false;
55
}
56
57
int16_t cin(unsigned timeout_ms)
58
{
59
uint8_t b = 0;
60
if (cin_data(&b, 1, timeout_ms)) {
61
return b;
62
}
63
return -1;
64
}
65
66
int cin_word(uint32_t *wp, unsigned timeout_ms)
67
{
68
if (cin_data((uint8_t *)wp, 4, timeout_ms)) {
69
return 0;
70
}
71
return -1;
72
}
73
74
75
void cout(uint8_t *data, uint32_t len)
76
{
77
chnWriteTimeout(uarts[last_uart], data, len, chTimeMS2I(100));
78
}
79
#endif // BOOTLOADER_DEV_LIST
80
81
static uint32_t flash_base_page;
82
static uint16_t num_pages;
83
static const uint8_t *flash_base = (const uint8_t *)(0x08000000 + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U);
84
85
/*
86
initialise flash_base_page and num_pages
87
*/
88
void flash_init(void)
89
{
90
uint32_t reserved = 0;
91
num_pages = stm32_flash_getnumpages();
92
/*
93
advance flash_base_page to account for (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)
94
*/
95
while (reserved < (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB) * 1024U &&
96
flash_base_page < num_pages) {
97
reserved += stm32_flash_getpagesize(flash_base_page);
98
flash_base_page++;
99
}
100
/*
101
reduce num_pages to account for FLASH_RESERVE_END_KB
102
*/
103
reserved = 0;
104
while (reserved < FLASH_RESERVE_END_KB * 1024U) {
105
reserved += stm32_flash_getpagesize(num_pages-1);
106
num_pages--;
107
}
108
}
109
110
void flash_set_keep_unlocked(bool set)
111
{
112
stm32_flash_keep_unlocked(set);
113
}
114
115
/*
116
read a word at offset relative to flash base
117
*/
118
119
#pragma GCC diagnostic push
120
#pragma GCC diagnostic ignored "-Wcast-align"
121
122
uint32_t flash_func_read_word(uint32_t offset)
123
{
124
return *(const uint32_t *)(flash_base + offset);
125
}
126
#pragma GCC diagnostic pop
127
128
bool flash_func_write_word(uint32_t offset, uint32_t v)
129
{
130
return stm32_flash_write(uint32_t(flash_base+offset), &v, sizeof(v));
131
}
132
133
bool flash_func_write_words(uint32_t offset, uint32_t *v, uint8_t n)
134
{
135
return stm32_flash_write(uint32_t(flash_base+offset), v, n*sizeof(*v));
136
}
137
138
uint32_t flash_func_sector_size(uint32_t sector)
139
{
140
if (sector >= num_pages-flash_base_page) {
141
return 0;
142
}
143
return stm32_flash_getpagesize(flash_base_page+sector);
144
}
145
146
bool flash_func_is_erased(uint32_t sector)
147
{
148
return stm32_flash_ispageerased(flash_base_page+sector);
149
}
150
151
bool flash_func_erase_sector(uint32_t sector, bool force_erase)
152
{
153
#if AP_BOOTLOADER_ALWAYS_ERASE
154
return stm32_flash_erasepage(flash_base_page+sector);
155
#else
156
if (force_erase || !stm32_flash_ispageerased(flash_base_page+sector)) {
157
return stm32_flash_erasepage(flash_base_page+sector);
158
}
159
return true;
160
#endif
161
}
162
163
// read one-time programmable memory
164
uint32_t flash_func_read_otp(uint32_t idx)
165
{
166
#ifndef OTP_SIZE
167
return 0;
168
#else
169
if (idx & 3) {
170
return 0;
171
}
172
173
if (idx > OTP_SIZE) {
174
return 0;
175
}
176
177
return *(uint32_t *)(idx + OTP_BASE);
178
#endif
179
}
180
181
// read chip serial number
182
uint32_t flash_func_read_sn(uint32_t idx)
183
{
184
return *(uint32_t *)(UDID_START + idx);
185
}
186
187
/*
188
we use a write buffer for flashing, both for efficiency and to
189
ensure that we only ever do 32 byte aligned writes on STM32H7. If
190
you attempt to do writes on a H7 of less than 32 bytes or not
191
aligned then the flash can end up in a CRC error state, which can
192
generate a hardware fault (a double ECC error) on flash read, even
193
after a power cycle
194
*/
195
static struct {
196
uint32_t buffer[8];
197
uint32_t address;
198
uint8_t n;
199
} fbuf;
200
201
/*
202
flush the write buffer
203
*/
204
bool flash_write_flush(void)
205
{
206
if (fbuf.n == 0) {
207
return true;
208
}
209
fbuf.n = 0;
210
return flash_func_write_words(fbuf.address, fbuf.buffer, ARRAY_SIZE(fbuf.buffer));
211
}
212
213
/*
214
write to flash with buffering to 32 bytes alignment
215
*/
216
bool flash_write_buffer(uint32_t address, const uint32_t *v, uint8_t nwords)
217
{
218
if (fbuf.n > 0 && address != fbuf.address + fbuf.n*4) {
219
if (!flash_write_flush()) {
220
return false;
221
}
222
}
223
while (nwords > 0) {
224
if (fbuf.n == 0) {
225
fbuf.address = address;
226
memset(fbuf.buffer, 0xff, sizeof(fbuf.buffer));
227
}
228
uint8_t n = MIN(ARRAY_SIZE(fbuf.buffer)-fbuf.n, nwords);
229
memcpy(&fbuf.buffer[fbuf.n], v, n*4);
230
address += n*4;
231
v += n;
232
nwords -= n;
233
fbuf.n += n;
234
if (fbuf.n == ARRAY_SIZE(fbuf.buffer)) {
235
if (!flash_write_flush()) {
236
return false;
237
}
238
}
239
}
240
return true;
241
}
242
243
uint32_t get_mcu_id(void)
244
{
245
return *(uint32_t *)DBGMCU_BASE;
246
}
247
248
#define REVID_MASK 0xFFFF0000
249
#define DEVID_MASK 0xFFF
250
251
uint32_t get_mcu_desc(uint32_t max, uint8_t *revstr)
252
{
253
uint32_t idcode = (*(uint32_t *)DBGMCU_BASE);
254
int32_t mcuid = idcode & DEVID_MASK;
255
uint16_t revid = ((idcode & REVID_MASK) >> 16);
256
257
uint8_t *endp = &revstr[max - 1];
258
uint8_t *strp = revstr;
259
260
for (const auto &desc : mcu_descriptions) {
261
if (mcuid == desc.mcuid) {
262
// copy the string in:
263
const char *tmp = desc.desc;
264
while (strp < endp && *tmp) {
265
*strp++ = *tmp++;
266
}
267
break;
268
}
269
}
270
271
// comma-separated:
272
if (strp < endp) {
273
*strp++ = ',';
274
}
275
276
for (const auto &rev : silicon_revs) {
277
if (rev.revid == revid) {
278
if (strp < endp) {
279
*strp++ = rev.rev;
280
}
281
}
282
}
283
284
return strp - revstr;
285
}
286
287
void led_on(unsigned led)
288
{
289
#ifdef HAL_GPIO_PIN_LED_BOOTLOADER
290
if (led == LED_BOOTLOADER) {
291
palWriteLine(HAL_GPIO_PIN_LED_BOOTLOADER, HAL_LED_ON);
292
}
293
#endif
294
#ifdef HAL_GPIO_PIN_LED_ACTIVITY
295
if (led == LED_ACTIVITY) {
296
palWriteLine(HAL_GPIO_PIN_LED_ACTIVITY, HAL_LED_ON);
297
}
298
#endif
299
}
300
301
void led_off(unsigned led)
302
{
303
#ifdef HAL_GPIO_PIN_LED_BOOTLOADER
304
if (led == LED_BOOTLOADER) {
305
palWriteLine(HAL_GPIO_PIN_LED_BOOTLOADER, !HAL_LED_ON);
306
}
307
#endif
308
#ifdef HAL_GPIO_PIN_LED_ACTIVITY
309
if (led == LED_ACTIVITY) {
310
palWriteLine(HAL_GPIO_PIN_LED_ACTIVITY, !HAL_LED_ON);
311
}
312
#endif
313
}
314
315
void led_toggle(unsigned led)
316
{
317
#ifdef HAL_GPIO_PIN_LED_BOOTLOADER
318
if (led == LED_BOOTLOADER) {
319
palToggleLine(HAL_GPIO_PIN_LED_BOOTLOADER);
320
}
321
#endif
322
#ifdef HAL_GPIO_PIN_LED_ACTIVITY
323
if (led == LED_ACTIVITY) {
324
palToggleLine(HAL_GPIO_PIN_LED_ACTIVITY);
325
}
326
#endif
327
}
328
329
extern "C" {
330
int vsnprintf(char *str, size_t size, const char *fmt, va_list ap);
331
}
332
333
// printf to USB for debugging
334
void uprintf(const char *fmt, ...)
335
{
336
#ifdef BOOTLOADER_DEBUG
337
va_list ap;
338
static bool initialised;
339
static SerialConfig debug_sercfg;
340
char umsg[200];
341
if (!initialised) {
342
initialised = true;
343
debug_sercfg.speed = 57600;
344
sdStart(&BOOTLOADER_DEBUG, &debug_sercfg);
345
}
346
va_start(ap, fmt);
347
uint32_t n = vsnprintf(umsg, sizeof(umsg), fmt, ap);
348
va_end(ap);
349
if (n > sizeof(umsg)) {
350
n = sizeof(umsg);
351
}
352
chnWriteTimeout(&BOOTLOADER_DEBUG, (const uint8_t *)umsg, n, chTimeMS2I(100));
353
#endif
354
}
355
356
void thread_sleep_ms(uint32_t ms)
357
{
358
while (ms > 0) {
359
// don't sleep more than 65 at a time, to cope with 16 bit
360
// timer
361
const uint32_t dt = ms > 65? 65: ms;
362
chThdSleepMilliseconds(dt);
363
ms -= dt;
364
}
365
}
366
367
void thread_sleep_us(uint32_t us)
368
{
369
while (us > 0) {
370
// don't sleep more than 65 at a time, to cope with 16 bit
371
// timer
372
const uint32_t dt = us > 6500? 6500: us;
373
chThdSleepMicroseconds(dt);
374
us -= dt;
375
}
376
}
377
378
// generate a pulse sequence forever, for debugging
379
void led_pulses(uint8_t npulses)
380
{
381
led_off(LED_BOOTLOADER);
382
while (true) {
383
for (uint8_t i=0; i<npulses; i++) {
384
led_on(LED_BOOTLOADER);
385
thread_sleep_ms(200);
386
led_off(LED_BOOTLOADER);
387
thread_sleep_ms(200);
388
}
389
thread_sleep_ms(2000);
390
}
391
}
392
393
//simple variant of std c function to reduce used flash space
394
void *memcpy(void *dest, const void *src, size_t n)
395
{
396
uint8_t *tdest = (uint8_t *)dest;
397
uint8_t *tsrc = (uint8_t *)src;
398
for (int i=0; i<n; i++) {
399
tdest[i] = tsrc[i];
400
}
401
return dest;
402
}
403
404
//simple variant of std c function to reduce used flash space
405
int strncmp(const char *s1, const char *s2, size_t n)
406
{
407
while ((*s1 != 0) && (*s1 == *s2) && n--) {
408
s1++;
409
s2++;
410
}
411
if (n == 0) {
412
return 0;
413
}
414
return (*s1 - *s2);
415
}
416
417
//simple variant of std c function to reduce used flash space
418
int strcmp(const char *s1, const char *s2)
419
{
420
while ((*s1 != 0) && (*s1 == *s2)) {
421
s1++;
422
s2++;
423
}
424
return (*s1 - *s2);
425
}
426
427
//simple variant of std c function to reduce used flash space
428
size_t strlen(const char *s1)
429
{
430
size_t ret = 0;
431
while (*s1++) ret++;
432
return ret;
433
}
434
435
//simple variant of std c function to reduce used flash space
436
void *memset(void *s, int c, size_t n)
437
{
438
uint8_t *b = (uint8_t *)s;
439
while (n--) {
440
*b++ = c;
441
}
442
return s;
443
}
444
445
#if defined(BOOTLOADER_DEV_LIST)
446
void lock_bl_port(void)
447
{
448
locked_uart = last_uart;
449
}
450
451
/*
452
initialise serial ports
453
*/
454
void init_uarts(void)
455
{
456
#if HAL_USE_SERIAL_USB == TRUE
457
sduObjectInit(&SDU1);
458
sduStart(&SDU1, &serusbcfg1);
459
#if HAL_HAVE_DUAL_USB_CDC
460
sduObjectInit(&SDU2);
461
sduStart(&SDU2, &serusbcfg2);
462
#endif
463
464
usbDisconnectBus(serusbcfg1.usbp);
465
thread_sleep_ms(1000);
466
usbStart(serusbcfg1.usbp, &usbcfg);
467
usbConnectBus(serusbcfg1.usbp);
468
#endif
469
470
#if HAL_USE_SERIAL == TRUE
471
sercfg.speed = BOOTLOADER_BAUDRATE;
472
473
for (const auto &uart : uarts) {
474
#if HAL_USE_SERIAL_USB == TRUE
475
if (uart == (BaseChannel *)&SDU1
476
#if HAL_HAVE_DUAL_USB_CDC
477
|| uart == (BaseChannel *)&SDU2
478
#endif
479
) {
480
continue;
481
}
482
#endif
483
sdStart((SerialDriver *)uart, &sercfg);
484
}
485
#endif
486
}
487
488
489
#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)
490
/* forward serial to OTG2
491
Used for devices containing multiple devices in one
492
*/
493
static SerialConfig forward_sercfg;
494
static uint32_t otg2_serial_deadline_ms;
495
bool update_otg2_serial_forward()
496
{
497
// get baudrate set on SDU2 and set it on HAL_FORWARD_OTG2_SERIAL if changed
498
if (forward_sercfg.speed != BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE) {
499
forward_sercfg.speed = BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE;
500
#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP) && BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP
501
forward_sercfg.cr2 = USART_CR2_SWAP;
502
#endif
503
sdStart(&BOOTLOADER_FORWARD_OTG2_SERIAL, &forward_sercfg);
504
}
505
// check how many bytes are available to read from HAL_FORWARD_OTG2_SERIAL
506
uint8_t data[SERIAL_BUFFERS_SIZE]; // read upto SERIAL_BUFFERS_SIZE at a time
507
int n = chnReadTimeout(&SDU2, data, SERIAL_BUFFERS_SIZE, TIME_IMMEDIATE);
508
if (n > 0) {
509
// do a blocking write to HAL_FORWARD_OTG2_SERIAL
510
chnWriteTimeout(&BOOTLOADER_FORWARD_OTG2_SERIAL, data, n, TIME_IMMEDIATE);
511
otg2_serial_deadline_ms = AP_HAL::millis() + 1000;
512
}
513
514
n = chnReadTimeout(&BOOTLOADER_FORWARD_OTG2_SERIAL, data, SERIAL_BUFFERS_SIZE, TIME_IMMEDIATE);
515
if (n > 0) {
516
// do a blocking write to SDU2
517
chnWriteTimeout(&SDU2, data, n, TIME_IMMEDIATE);
518
}
519
520
return (AP_HAL::millis() < otg2_serial_deadline_ms);
521
}
522
#endif
523
524
/*
525
set baudrate on the current port
526
*/
527
void port_setbaud(uint32_t baudrate)
528
{
529
#if HAL_USE_SERIAL_USB == TRUE
530
if (uarts[last_uart] == (BaseChannel *)&SDU1
531
#if HAL_HAVE_DUAL_USB_CDC
532
|| uarts[last_uart] == (BaseChannel *)&SDU2
533
#endif
534
) {
535
// can't set baudrate on USB
536
return;
537
}
538
#endif
539
#if HAL_USE_SERIAL == TRUE
540
memset(&sercfg, 0, sizeof(sercfg));
541
sercfg.speed = baudrate;
542
sdStart((SerialDriver *)uarts[last_uart], &sercfg);
543
#endif
544
}
545
#endif // BOOTLOADER_DEV_LIST
546
547
#if defined(STM32H7) && CH_CFG_USE_HEAP
548
/*
549
check if flash has any ECC errors and if it does then erase all of
550
flash
551
*/
552
#define ECC_CHECK_CHUNK_SIZE (32*sizeof(uint32_t))
553
void check_ecc_errors(void)
554
{
555
__disable_fault_irq();
556
// stm32_flash_corrupt(0x8043200);
557
auto *dma = dmaStreamAlloc(STM32_DMA_STREAM_ID(1, 1), 0, nullptr, nullptr);
558
559
uint32_t *buf = (uint32_t*)malloc_dma(ECC_CHECK_CHUNK_SIZE);
560
561
if (buf == nullptr) {
562
// DMA'ble memory not available
563
return;
564
}
565
uint32_t ofs = 0;
566
while (ofs < BOARD_FLASH_SIZE*1024) {
567
if (FLASH->SR1 & (FLASH_SR_SNECCERR | FLASH_SR_DBECCERR)) {
568
break;
569
}
570
#if BOARD_FLASH_SIZE > 1024
571
if (FLASH->SR2 & (FLASH_SR_SNECCERR | FLASH_SR_DBECCERR)) {
572
break;
573
}
574
#endif
575
dmaStartMemCopy(dma,
576
STM32_DMA_CR_PL(0) | STM32_DMA_CR_PSIZE_BYTE |
577
STM32_DMA_CR_MSIZE_BYTE,
578
ofs+(uint8_t*)FLASH_BASE, buf, ECC_CHECK_CHUNK_SIZE);
579
dmaWaitCompletion(dma);
580
ofs += ECC_CHECK_CHUNK_SIZE;
581
}
582
dmaStreamFree(dma);
583
584
if (ofs < BOARD_FLASH_SIZE*1024) {
585
// we must have ECC errors in flash
586
flash_set_keep_unlocked(true);
587
for (uint32_t i=0; i<num_pages; i++) {
588
stm32_flash_erasepage(flash_base_page+i);
589
}
590
flash_set_keep_unlocked(false);
591
}
592
__enable_fault_irq();
593
}
594
#endif // defined(STM32H7) && CH_CFG_USE_HEAP
595
596
597