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