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/bl_protocol.cpp
Views: 1798
1
/*
2
ArduPilot bootloader protocol
3
4
based on bl.c from https://github.com/PX4/Bootloader.
5
6
Ported to ChibiOS for ArduPilot by Andrew Tridgell
7
*/
8
9
/****************************************************************************
10
*
11
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
12
*
13
* Redistribution and use in source and binary forms, with or without
14
* modification, are permitted provided that the following conditions
15
* are met:
16
*
17
* 1. Redistributions of source code must retain the above copyright
18
* notice, this list of conditions and the following disclaimer.
19
* 2. Redistributions in binary form must reproduce the above copyright
20
* notice, this list of conditions and the following disclaimer in
21
* the documentation and/or other materials provided with the
22
* distribution.
23
* 3. Neither the name PX4 nor the names of its contributors may be
24
* used to endorse or promote products derived from this software
25
* without specific prior written permission.
26
*
27
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
28
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
29
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
30
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
31
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
32
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
33
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
34
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
35
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
36
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
37
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
38
* POSSIBILITY OF SUCH DAMAGE.
39
*
40
****************************************************************************/
41
42
#include <AP_HAL/AP_HAL.h>
43
#include <AP_Math/AP_Math.h>
44
#include <AP_Math/crc.h>
45
#include "ch.h"
46
#include "hal.h"
47
#include "hwdef.h"
48
49
#include "bl_protocol.h"
50
#include "support.h"
51
#include "can.h"
52
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
53
#if EXT_FLASH_SIZE_MB
54
#include <AP_FlashIface/AP_FlashIface_JEDEC.h>
55
#endif
56
#include <AP_CheckFirmware/AP_CheckFirmware.h>
57
58
// #pragma GCC optimize("O0")
59
60
61
// bootloader flash update protocol.
62
//
63
// Command format:
64
//
65
// <opcode>[<command_data>]<EOC>
66
//
67
// Reply format:
68
//
69
// [<reply_data>]<INSYNC><status>
70
//
71
// The <opcode> and <status> values come from the PROTO_ defines below,
72
// the <*_data> fields is described only for opcodes that transfer data;
73
// in all other cases the field is omitted.
74
//
75
// Expected workflow (protocol 3) is:
76
//
77
// GET_SYNC verify that the board is present
78
// GET_DEVICE determine which board (select firmware to upload)
79
// CHIP_ERASE erase the program area and reset address counter
80
// loop:
81
// PROG_MULTI program bytes
82
// GET_CRC verify CRC of entire flashable area
83
// RESET finalise flash programming, reset chip and starts application
84
//
85
86
#define BL_PROTOCOL_VERSION 5 // The revision of the bootloader protocol
87
// protocol bytes
88
#define PROTO_INSYNC 0x12 // 'in sync' byte sent before status
89
#define PROTO_EOC 0x20 // end of command
90
91
// Reply bytes
92
#define PROTO_OK 0x10 // INSYNC/OK - 'ok' response
93
#define PROTO_FAILED 0x11 // INSYNC/FAILED - 'fail' response
94
#define PROTO_INVALID 0x13 // INSYNC/INVALID - 'invalid' response for bad commands
95
#define PROTO_BAD_SILICON_REV 0x14 // On the F4 series there is an issue with < Rev 3 silicon
96
// see https://pixhawk.org/help/errata
97
// Command bytes
98
#define PROTO_GET_SYNC 0x21 // NOP for re-establishing sync
99
#define PROTO_GET_DEVICE 0x22 // get device ID bytes
100
#define PROTO_CHIP_ERASE 0x23 // erase program area and reset program address
101
#define PROTO_PROG_MULTI 0x27 // write bytes at program address and increment
102
#define PROTO_READ_MULTI 0x28 // read bytes at address and increment
103
#define PROTO_GET_CRC 0x29 // compute & return a CRC
104
#define PROTO_GET_OTP 0x2a // read a byte from OTP at the given address
105
#define PROTO_GET_SN 0x2b // read a word from UDID area ( Serial) at the given address
106
#define PROTO_GET_CHIP 0x2c // read chip version (MCU IDCODE)
107
#define PROTO_SET_DELAY 0x2d // set minimum boot delay
108
#define PROTO_GET_CHIP_DES 0x2e // read chip version In ASCII
109
#define PROTO_BOOT 0x30 // boot the application
110
#define PROTO_DEBUG 0x31 // emit debug information - format not defined
111
#define PROTO_SET_BAUD 0x33 // baud rate on uart
112
113
// External Flash programming
114
#define PROTO_EXTF_ERASE 0x34 // Erase sectors from external flash
115
#define PROTO_EXTF_PROG_MULTI 0x35 // write bytes at external flash program address and increment
116
#define PROTO_EXTF_READ_MULTI 0x36 // read bytes at address and increment
117
#define PROTO_EXTF_GET_CRC 0x37 // compute & return a CRC of data in external flash
118
119
#define PROTO_CHIP_FULL_ERASE 0x40 // erase program area and reset program address, skip any flash wear optimization and force an erase
120
121
#define PROTO_PROG_MULTI_MAX 64 // maximum PROG_MULTI size
122
#define PROTO_READ_MULTI_MAX 255 // size of the size field
123
124
/* argument values for PROTO_GET_DEVICE */
125
#define PROTO_DEVICE_BL_REV 1 // bootloader revision
126
#define PROTO_DEVICE_BOARD_ID 2 // board ID
127
#define PROTO_DEVICE_BOARD_REV 3 // board revision
128
#define PROTO_DEVICE_FW_SIZE 4 // size of flashable area
129
#define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10
130
#define PROTO_DEVICE_EXTF_SIZE 6 // size of available external flash
131
// all except PROTO_DEVICE_VEC_AREA and PROTO_DEVICE_BOARD_REV should be done
132
#define CHECK_GET_DEVICE_FINISHED(x) ((x & (0xB)) == 0xB)
133
134
// interrupt vector table for STM32
135
#define SCB_VTOR 0xE000ED08
136
137
static virtual_timer_t systick_vt;
138
139
/*
140
millisecond timer array
141
*/
142
#define NTIMERS 2
143
#define TIMER_BL_WAIT 0
144
#define TIMER_LED 1
145
146
static enum led_state led_state;
147
148
volatile unsigned timer[NTIMERS];
149
150
// keep back 32 bytes at the front of flash. This is long enough to allow for aligned
151
// access on STM32H7
152
#define RESERVE_LEAD_WORDS 8
153
154
155
#if EXT_FLASH_SIZE_MB
156
extern AP_FlashIface_JEDEC ext_flash;
157
#endif
158
159
#ifndef BOOT_FROM_EXT_FLASH
160
#define BOOT_FROM_EXT_FLASH 0
161
#endif
162
163
/*
164
1ms timer tick callback
165
*/
166
static void sys_tick_handler(virtual_timer_t* vt, void *ctx)
167
{
168
chSysLockFromISR();
169
chVTSetI(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);
170
chSysUnlockFromISR();
171
uint8_t i;
172
for (i = 0; i < NTIMERS; i++)
173
if (timer[i] > 0) {
174
timer[i]--;
175
}
176
177
if ((led_state == LED_BLINK) && (timer[TIMER_LED] == 0)) {
178
led_toggle(LED_BOOTLOADER);
179
timer[TIMER_LED] = 50;
180
}
181
182
if ((led_state == LED_BAD_FW) && (timer[TIMER_LED] == 0)) {
183
led_toggle(LED_BOOTLOADER);
184
timer[TIMER_LED] = 1000;
185
}
186
}
187
188
static void delay(unsigned msec)
189
{
190
chThdSleep(chTimeMS2I(msec));
191
}
192
193
void
194
led_set(enum led_state state)
195
{
196
led_state = state;
197
198
switch (state) {
199
case LED_OFF:
200
led_off(LED_BOOTLOADER);
201
break;
202
203
case LED_ON:
204
led_on(LED_BOOTLOADER);
205
break;
206
207
case LED_BLINK:
208
/* restart the blink state machine ASAP */
209
timer[TIMER_LED] = 0;
210
break;
211
212
case LED_BAD_FW:
213
timer[TIMER_LED] = 0;
214
break;
215
}
216
}
217
218
static void
219
do_jump(uint32_t stacktop, uint32_t entrypoint)
220
{
221
#if defined(STM32F7) || defined(STM32H7)
222
// disable caches on F7 before starting program
223
__DSB();
224
__ISB();
225
SCB_DisableDCache();
226
SCB_DisableICache();
227
#endif
228
229
chSysLock();
230
231
// we set sp as well as msp to avoid an issue with loading NuttX
232
asm volatile(
233
"mov sp, %0 \n"
234
"msr msp, %0 \n"
235
"bx %1 \n"
236
: : "r"(stacktop), "r"(entrypoint) :);
237
}
238
239
#ifndef APP_START_ADDRESS
240
#define APP_START_ADDRESS (FLASH_LOAD_ADDRESS + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U)
241
#endif
242
243
#if !defined(STM32_OTG2_IS_OTG1)
244
#define STM32_OTG2_IS_OTG1 0
245
#endif
246
247
void
248
jump_to_app()
249
{
250
const uint32_t *app_base = (const uint32_t *)(APP_START_ADDRESS);
251
252
#if AP_CHECK_FIRMWARE_ENABLED
253
const auto ok = check_good_firmware();
254
if (ok != check_fw_result_t::CHECK_FW_OK) {
255
// bad firmware, don't try and boot
256
led_set(LED_BAD_FW);
257
return;
258
}
259
#endif
260
261
// If we have QSPI chip start it
262
#if EXT_FLASH_SIZE_MB
263
uint8_t* ext_flash_start_addr;
264
if (!ext_flash.start_xip_mode((void**)&ext_flash_start_addr)) {
265
return;
266
}
267
#endif
268
/*
269
* We hold back the programming of the lead words until the upload
270
* is marked complete by the host. So if they are not 0xffffffff,
271
* we should try booting it.
272
*/
273
for (uint8_t i=0; i<RESERVE_LEAD_WORDS; i++) {
274
if (app_base[i] == 0xffffffff) {
275
goto exit;
276
}
277
}
278
279
/*
280
* The second word of the app is the entrypoint; it must point within the
281
* flash area (or we have a bad flash).
282
*/
283
if (app_base[1] < APP_START_ADDRESS) {
284
goto exit;
285
}
286
287
#if BOOT_FROM_EXT_FLASH
288
if (app_base[1] >= (APP_START_ADDRESS + board_info.extf_size)) {
289
goto exit;
290
}
291
#else
292
if (app_base[1] >= (APP_START_ADDRESS + board_info.fw_size)) {
293
goto exit;
294
}
295
#endif
296
297
#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES
298
// for CAN firmware we start the watchdog before we run the
299
// application code, to ensure we catch a bad firmare. If we get a
300
// watchdog reset and the firmware hasn't changed the RTC flag to
301
// indicate that it has been running OK for 30s then we will stay
302
// in bootloader
303
#ifndef DISABLE_WATCHDOG
304
stm32_watchdog_init();
305
#endif
306
stm32_watchdog_pat();
307
#endif
308
309
flash_set_keep_unlocked(false);
310
311
led_set(LED_OFF);
312
313
// resetting the clocks is needed for loading NuttX
314
#if defined(STM32H7)
315
rccDisableAPB1L(~0);
316
rccDisableAPB1H(~0);
317
#elif defined(STM32G4)
318
rccDisableAPB1R1(~0);
319
rccDisableAPB1R2(~0);
320
#elif defined(STM32L4)
321
rccDisableAPB1R1(~0);
322
rccDisableAPB1R2(~0);
323
#elif defined(STM32L4PLUS)
324
rccDisableAPB1R1(~0);
325
rccDisableAPB1R2(~0);
326
#else
327
rccDisableAPB1(~0);
328
#endif
329
rccDisableAPB2(~0);
330
#if HAL_USE_SERIAL_USB == TRUE
331
#if !STM32_OTG2_IS_OTG1
332
rccResetOTG_FS();
333
#endif
334
#if defined(rccResetOTG_HS)
335
rccResetOTG_HS();
336
#endif
337
#endif
338
339
// disable all interrupt sources
340
port_disable();
341
342
/* switch exception handlers to the application */
343
*(volatile uint32_t *)SCB_VTOR = APP_START_ADDRESS;
344
345
/* extract the stack and entrypoint from the app vector table and go */
346
do_jump(app_base[0], app_base[1]);
347
exit:
348
#if EXT_FLASH_SIZE_MB
349
ext_flash.stop_xip_mode();
350
#endif
351
return;
352
}
353
354
static void
355
sync_response(void)
356
{
357
uint8_t data[] = {
358
PROTO_INSYNC, // "in sync"
359
PROTO_OK // "OK"
360
};
361
362
cout(data, sizeof(data));
363
}
364
365
static void
366
invalid_response(void)
367
{
368
uint8_t data[] = {
369
PROTO_INSYNC, // "in sync"
370
PROTO_INVALID // "invalid command"
371
};
372
373
cout(data, sizeof(data));
374
}
375
376
static void
377
failure_response(void)
378
{
379
uint8_t data[] = {
380
PROTO_INSYNC, // "in sync"
381
PROTO_FAILED // "command failed"
382
};
383
384
cout(data, sizeof(data));
385
}
386
387
/**
388
* Function to wait for EOC
389
*
390
* @param timeout length of time in ms to wait for the EOC to be received
391
* @return true if the EOC is returned within the timeout perio, else false
392
*/
393
inline static bool
394
wait_for_eoc(unsigned timeout)
395
{
396
return cin(timeout) == PROTO_EOC;
397
}
398
399
static void
400
cout_word(uint32_t val)
401
{
402
cout((uint8_t *)&val, 4);
403
}
404
405
#define TEST_FLASH 0
406
407
#if TEST_FLASH
408
static void test_flash()
409
{
410
uint32_t loop = 1;
411
bool init_done = false;
412
while (true) {
413
uint32_t addr = 0;
414
uint32_t page = 0;
415
while (true) {
416
uint32_t v[8];
417
for (uint8_t i=0; i<8; i++) {
418
v[i] = (page<<16) + loop;
419
}
420
if (flash_func_sector_size(page) == 0) {
421
continue;
422
}
423
uint32_t num_writes = flash_func_sector_size(page) / sizeof(v);
424
uprintf("page %u size %u addr=0x%08x v=0x%08x\n",
425
unsigned(page), unsigned(flash_func_sector_size(page)), unsigned(addr), unsigned(v[0])); delay(10);
426
if (init_done) {
427
for (uint32_t j=0; j<flash_func_sector_size(page)/4; j++) {
428
uint32_t v1 = (page<<16) + (loop-1);
429
uint32_t v2 = flash_func_read_word(addr+j*4);
430
if (v2 != v1) {
431
uprintf("read error at 0x%08x v=0x%08x v2=0x%08x\n", unsigned(addr+j*4), unsigned(v1), unsigned(v2));
432
break;
433
}
434
}
435
}
436
if (!flash_func_erase_sector(page)) {
437
uprintf("erase of %u failed\n", unsigned(page));
438
}
439
for (uint32_t j=0; j<num_writes; j++) {
440
if (!flash_func_write_words(addr+j*sizeof(v), v, ARRAY_SIZE(v))) {
441
uprintf("write failed at 0x%08x\n", unsigned(addr+j*sizeof(v)));
442
break;
443
}
444
}
445
addr += flash_func_sector_size(page);
446
page++;
447
if (flash_func_sector_size(page) == 0) {
448
break;
449
}
450
}
451
init_done = true;
452
delay(1000);
453
loop++;
454
}
455
}
456
#endif
457
458
void
459
bootloader(unsigned timeout)
460
{
461
#if TEST_FLASH
462
test_flash();
463
#endif
464
465
uint32_t address = board_info.fw_size; /* force erase before upload will work */
466
#if EXT_FLASH_SIZE_MB
467
uint32_t extf_address = board_info.extf_size; /* force erase before upload will work */
468
#endif
469
uint32_t read_address = 0;
470
uint32_t first_words[RESERVE_LEAD_WORDS];
471
bool done_sync = false;
472
uint8_t done_get_device_flags = 0;
473
bool done_erase = false;
474
static bool done_timer_init;
475
unsigned original_timeout = timeout;
476
477
memset(first_words, 0xFF, sizeof(first_words));
478
479
if (!done_timer_init) {
480
done_timer_init = true;
481
chVTObjectInit(&systick_vt);
482
chVTSet(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);
483
}
484
485
/* if we are working with a timeout, start it running */
486
if (timeout) {
487
timer[TIMER_BL_WAIT] = timeout;
488
}
489
490
/* make the LED blink while we are idle */
491
// ensure we don't override BAD FW LED
492
if (led_state != LED_BAD_FW) {
493
led_set(LED_BLINK);
494
}
495
496
while (true) {
497
volatile int c;
498
int arg;
499
static union {
500
uint8_t c[256];
501
uint32_t w[64];
502
} flash_buffer;
503
504
// Wait for a command byte
505
led_off(LED_ACTIVITY);
506
507
do {
508
/* if we have a timeout and the timer has expired and serial forward is not busy, return now */
509
#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)
510
bool ser_forward_active = update_otg2_serial_forward();
511
#endif
512
if (timeout && !timer[TIMER_BL_WAIT]
513
#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)
514
// do serial forward only when idle
515
&& !ser_forward_active
516
#endif
517
) {
518
return;
519
}
520
521
/* try to get a byte from the host */
522
c = cin(0);
523
#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES
524
if (c < 0) {
525
can_update();
526
}
527
#endif
528
} while (c < 0);
529
530
led_on(LED_ACTIVITY);
531
532
// handle the command byte
533
switch (c) {
534
535
// sync
536
//
537
// command: GET_SYNC/EOC
538
// reply: INSYNC/OK
539
//
540
case PROTO_GET_SYNC:
541
542
/* expect EOC */
543
if (!wait_for_eoc(2)) {
544
goto cmd_bad;
545
}
546
done_sync = true;
547
break;
548
549
// get device info
550
//
551
// command: GET_DEVICE/<arg:1>/EOC
552
// BL_REV reply: <revision:4>/INSYNC/EOC
553
// BOARD_ID reply: <board type:4>/INSYNC/EOC
554
// BOARD_REV reply: <board rev:4>/INSYNC/EOC
555
// FW_SIZE reply: <firmware size:4>/INSYNC/EOC
556
// VEC_AREA reply <vectors 7-10:16>/INSYNC/EOC
557
// bad arg reply: INSYNC/INVALID
558
//
559
case PROTO_GET_DEVICE:
560
/* expect arg then EOC */
561
arg = cin(1000);
562
563
if (arg < 0) {
564
goto cmd_bad;
565
}
566
567
if (!wait_for_eoc(2)) {
568
goto cmd_bad;
569
}
570
571
// reset read pointer
572
read_address = 0;
573
574
switch (arg) {
575
case PROTO_DEVICE_BL_REV: {
576
uint32_t bl_proto_rev = BL_PROTOCOL_VERSION;
577
cout((uint8_t *)&bl_proto_rev, sizeof(bl_proto_rev));
578
break;
579
}
580
581
case PROTO_DEVICE_BOARD_ID:
582
cout((uint8_t *)&board_info.board_type, sizeof(board_info.board_type));
583
break;
584
585
case PROTO_DEVICE_BOARD_REV:
586
cout((uint8_t *)&board_info.board_rev, sizeof(board_info.board_rev));
587
break;
588
589
case PROTO_DEVICE_FW_SIZE:
590
cout((uint8_t *)&board_info.fw_size, sizeof(board_info.fw_size));
591
break;
592
593
case PROTO_DEVICE_VEC_AREA:
594
for (unsigned p = 7; p <= 10; p++) {
595
uint32_t bytes = flash_func_read_word(p * 4);
596
597
cout((uint8_t *)&bytes, sizeof(bytes));
598
}
599
600
break;
601
602
case PROTO_DEVICE_EXTF_SIZE:
603
cout((uint8_t *)&board_info.extf_size, sizeof(board_info.extf_size));
604
break;
605
606
default:
607
goto cmd_bad;
608
}
609
done_get_device_flags |= (1<<(arg-1)); // set the flags for use when resetting timeout
610
break;
611
612
// erase and prepare for programming
613
//
614
// command: ERASE/EOC
615
// success reply: INSYNC/OK
616
// erase failure: INSYNC/FAILURE
617
//
618
case PROTO_CHIP_ERASE:
619
#if defined(STM32F7) || defined(STM32H7)
620
case PROTO_CHIP_FULL_ERASE:
621
#endif
622
623
if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {
624
// lower chance of random data on a uart triggering erase
625
goto cmd_bad;
626
}
627
628
/* expect EOC */
629
if (!wait_for_eoc(2)) {
630
goto cmd_bad;
631
}
632
633
// once erase is done there is no going back, set timeout
634
// to zero
635
done_erase = true;
636
timeout = 0;
637
638
flash_set_keep_unlocked(true);
639
640
// clear the bootloader LED while erasing - it stops blinking at random
641
// and that's confusing
642
led_set(LED_OFF);
643
644
// erase all sectors
645
for (uint16_t i = 0; flash_func_sector_size(i) != 0; i++) {
646
#if defined(STM32F7) || defined(STM32H7)
647
if (!flash_func_erase_sector(i, c == PROTO_CHIP_FULL_ERASE)) {
648
#else
649
if (!flash_func_erase_sector(i)) {
650
#endif
651
goto cmd_fail;
652
}
653
}
654
655
// enable the LED while verifying the erase
656
led_set(LED_ON);
657
658
// verify the erase
659
for (address = 0; address < board_info.fw_size; address += 4) {
660
if (flash_func_read_word(address) != 0xffffffff) {
661
goto cmd_fail;
662
}
663
}
664
665
address = 0;
666
667
// resume blinking
668
led_set(LED_BLINK);
669
break;
670
671
// program data from start of the flash
672
//
673
// command: EXTF_ERASE/<len:4>/EOC
674
// success reply: INSYNC/OK
675
// invalid reply: INSYNC/INVALID
676
// readback failure: INSYNC/FAILURE
677
//
678
case PROTO_EXTF_ERASE:
679
#if EXT_FLASH_SIZE_MB
680
{
681
if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {
682
// lower chance of random data on a uart triggering erase
683
goto cmd_bad;
684
}
685
uint32_t cmd_erase_bytes;
686
if (cin_word(&cmd_erase_bytes, 100)) {
687
goto cmd_bad;
688
}
689
690
// expect EOC
691
if (!wait_for_eoc(2)) {
692
goto cmd_bad;
693
}
694
uint32_t erased_bytes = 0;
695
uint32_t sector_number = EXT_FLASH_RESERVE_START_KB * 1024 / ext_flash.get_sector_size();
696
uint8_t pct_done = 0;
697
if (cmd_erase_bytes > (ext_flash.get_sector_size() * ext_flash.get_sector_count())) {
698
uprintf("Requested to erase more than we can\n");
699
goto cmd_bad;
700
}
701
uprintf("Erase Command Received\n");
702
sync_response();
703
cout(&pct_done, sizeof(pct_done));
704
// Flash all sectors that encompass the erase_bytes
705
while (erased_bytes < cmd_erase_bytes) {
706
uint32_t delay_ms = 0, timeout_ms = 0;
707
if (!ext_flash.start_sector_erase(sector_number, delay_ms, timeout_ms)) {
708
goto cmd_fail;
709
}
710
uint32_t next_check_ms = AP_HAL::millis() + delay_ms;
711
while (true) {
712
cout(&pct_done, sizeof(pct_done));
713
if (AP_HAL::millis() > next_check_ms) {
714
if (!ext_flash.is_device_busy()) {
715
pct_done = erased_bytes*100/cmd_erase_bytes;
716
uprintf("PCT DONE: %d\n", pct_done);
717
break;
718
}
719
if ((AP_HAL::millis() + timeout_ms) > next_check_ms) {
720
// We are out of time, return error
721
goto cmd_fail;
722
}
723
next_check_ms = AP_HAL::millis()+delay_ms;
724
}
725
chThdSleep(chTimeMS2I(delay_ms));
726
}
727
erased_bytes += ext_flash.get_sector_size();
728
sector_number++;
729
}
730
pct_done = 100;
731
extf_address = 0;
732
cout(&pct_done, sizeof(pct_done));
733
}
734
#else
735
goto cmd_bad;
736
#endif // EXT_FLASH_SIZE_MB
737
break;
738
739
// program bytes at current external flash address
740
//
741
// command: PROG_MULTI/<len:1>/<data:len>/EOC
742
// success reply: INSYNC/OK
743
// invalid reply: INSYNC/INVALID
744
// readback failure: INSYNC/FAILURE
745
//
746
case PROTO_EXTF_PROG_MULTI:
747
{
748
#if EXT_FLASH_SIZE_MB
749
if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {
750
// lower chance of random data on a uart triggering erase
751
goto cmd_bad;
752
}
753
754
// expect count
755
led_set(LED_OFF);
756
757
arg = cin(50);
758
759
if (arg < 0) {
760
goto cmd_bad;
761
}
762
763
if ((extf_address + arg) > board_info.extf_size) {
764
goto cmd_bad;
765
}
766
767
if (arg > sizeof(flash_buffer.c)) {
768
goto cmd_bad;
769
}
770
771
for (int i = 0; i < arg; i++) {
772
c = cin(1000);
773
774
if (c < 0) {
775
goto cmd_bad;
776
}
777
778
flash_buffer.c[i] = c;
779
}
780
781
if (!wait_for_eoc(200)) {
782
goto cmd_bad;
783
}
784
785
uint32_t offset = 0;
786
uint32_t size = arg;
787
#if BOOT_FROM_EXT_FLASH
788
// save the first words and don't program it until everything else is done
789
if (extf_address < sizeof(first_words)) {
790
uint8_t n = MIN(sizeof(first_words)-extf_address, arg);
791
memcpy(&first_words[extf_address/4], &flash_buffer.w[0], n);
792
// replace first words with 1 bits we can overwrite later
793
memset(&flash_buffer.w[0], 0xFF, n);
794
}
795
#endif
796
uint32_t programming;
797
uint32_t delay_us = 0, timeout_us = 0;
798
uint64_t start_time_us;
799
while (true) {
800
if (size == 0) {
801
extf_address += arg;
802
break;
803
}
804
if (!ext_flash.start_program_offset(extf_address+offset+EXT_FLASH_RESERVE_START_KB*1024,
805
&flash_buffer.c[offset], size, programming, delay_us, timeout_us)) {
806
// uprintf("ext flash write command failed\n");
807
goto cmd_fail;
808
}
809
start_time_us = AP_HAL::micros64();
810
// prepare for next run
811
offset += programming;
812
size -= programming;
813
while (true) {
814
if (AP_HAL::micros64() > (start_time_us+delay_us)) {
815
if (!ext_flash.is_device_busy()) {
816
// uprintf("flash program Successful, elapsed %ld us\n", uint32_t(AP_HAL::micros64() - start_time_us));
817
break;
818
} else {
819
// uprintf("Typical flash program time reached, Still Busy?!\n");
820
}
821
}
822
}
823
}
824
#endif
825
break;
826
}
827
828
// program bytes at current address
829
//
830
// command: PROG_MULTI/<len:1>/<data:len>/EOC
831
// success reply: INSYNC/OK
832
// invalid reply: INSYNC/INVALID
833
// readback failure: INSYNC/FAILURE
834
//
835
case PROTO_PROG_MULTI: // program bytes
836
if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {
837
// lower chance of random data on a uart triggering erase
838
goto cmd_bad;
839
}
840
841
// expect count
842
led_set(LED_OFF);
843
844
arg = cin(50);
845
846
if (arg < 0) {
847
goto cmd_bad;
848
}
849
850
// sanity-check arguments
851
if (arg % 4) {
852
goto cmd_bad;
853
}
854
855
if ((address + arg) > board_info.fw_size) {
856
goto cmd_bad;
857
}
858
859
if (arg > sizeof(flash_buffer.c)) {
860
goto cmd_bad;
861
}
862
863
for (int i = 0; i < arg; i++) {
864
c = cin(1000);
865
866
if (c < 0) {
867
goto cmd_bad;
868
}
869
870
flash_buffer.c[i] = c;
871
}
872
873
if (!wait_for_eoc(200)) {
874
goto cmd_bad;
875
}
876
877
// save the first words and don't program it until everything else is done
878
#if !BOOT_FROM_EXT_FLASH
879
if (address < sizeof(first_words)) {
880
uint8_t n = MIN(sizeof(first_words)-address, arg);
881
memcpy(&first_words[address/4], &flash_buffer.w[0], n);
882
// replace first words with 1 bits we can overwrite later
883
memset(&flash_buffer.w[0], 0xFF, n);
884
}
885
#endif
886
arg /= 4;
887
// program the words
888
if (!flash_write_buffer(address, flash_buffer.w, arg)) {
889
goto cmd_fail;
890
}
891
address += arg * 4;
892
break;
893
894
// fetch CRC of the entire flash area
895
//
896
// command: GET_CRC/EOC
897
// reply: <crc:4>/INSYNC/OK
898
//
899
case PROTO_GET_CRC: {
900
// expect EOC
901
if (!wait_for_eoc(2)) {
902
goto cmd_bad;
903
}
904
905
if (!flash_write_flush()) {
906
goto cmd_bad;
907
}
908
909
// compute CRC of the programmed area
910
uint32_t sum = 0;
911
912
for (unsigned p = 0; p < board_info.fw_size; p += 4) {
913
uint32_t bytes;
914
915
#if !BOOT_FROM_EXT_FLASH
916
if (p < sizeof(first_words) && first_words[0] != 0xFFFFFFFF) {
917
bytes = first_words[p/4];
918
} else
919
#endif
920
{
921
bytes = flash_func_read_word(p);
922
}
923
sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes));
924
}
925
926
cout_word(sum);
927
break;
928
}
929
930
// fetch CRC of the external flash area
931
//
932
// command: EXTF_GET_CRC/<len:4>/EOC
933
// reply: <crc:4>/INSYNC/OK
934
//
935
case PROTO_EXTF_GET_CRC: {
936
#if EXT_FLASH_SIZE_MB
937
// expect EOC
938
uint32_t cmd_verify_bytes;
939
if (cin_word(&cmd_verify_bytes, 100)) {
940
goto cmd_bad;
941
}
942
943
if (!wait_for_eoc(2)) {
944
goto cmd_bad;
945
}
946
947
// compute CRC of the programmed area
948
uint32_t sum = 0;
949
uint8_t rembytes = cmd_verify_bytes % 4;
950
for (unsigned p = 0; p < (cmd_verify_bytes-rembytes); p+=4) {
951
uint32_t bytes;
952
953
#if BOOT_FROM_EXT_FLASH
954
if (p < sizeof(first_words) && first_words[0] != 0xFFFFFFFF) {
955
bytes = first_words[p/4];
956
} else
957
#endif
958
{
959
ext_flash.read(p+EXT_FLASH_RESERVE_START_KB*1024, (uint8_t *)&bytes, sizeof(bytes));
960
}
961
sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes));
962
}
963
if (rembytes) {
964
uint8_t bytes[3];
965
ext_flash.read(EXT_FLASH_RESERVE_START_KB*1024+cmd_verify_bytes-rembytes, bytes, rembytes);
966
sum = crc32_small(sum, bytes, rembytes);
967
}
968
cout_word(sum);
969
break;
970
#endif
971
}
972
973
// read a word from the OTP
974
//
975
// command: GET_OTP/<addr:4>/EOC
976
// reply: <value:4>/INSYNC/OK
977
case PROTO_GET_OTP:
978
// expect argument
979
{
980
uint32_t index = 0;
981
982
if (cin_word(&index, 100)) {
983
goto cmd_bad;
984
}
985
986
// expect EOC
987
if (!wait_for_eoc(2)) {
988
goto cmd_bad;
989
}
990
991
cout_word(flash_func_read_otp(index));
992
}
993
break;
994
995
// read the SN from the UDID
996
//
997
// command: GET_SN/<addr:4>/EOC
998
// reply: <value:4>/INSYNC/OK
999
case PROTO_GET_SN:
1000
// expect argument
1001
{
1002
uint32_t index = 0;
1003
1004
if (cin_word(&index, 100)) {
1005
goto cmd_bad;
1006
}
1007
1008
// expect EOC
1009
if (!wait_for_eoc(2)) {
1010
goto cmd_bad;
1011
}
1012
1013
cout_word(flash_func_read_sn(index));
1014
}
1015
break;
1016
1017
// read the chip ID code
1018
//
1019
// command: GET_CHIP/EOC
1020
// reply: <value:4>/INSYNC/OK
1021
case PROTO_GET_CHIP: {
1022
// expect EOC
1023
if (!wait_for_eoc(2)) {
1024
goto cmd_bad;
1025
}
1026
1027
cout_word(get_mcu_id());
1028
}
1029
break;
1030
1031
// read the chip description
1032
//
1033
// command: GET_CHIP_DES/EOC
1034
// reply: <value:4>/INSYNC/OK
1035
case PROTO_GET_CHIP_DES: {
1036
uint8_t buffer[MAX_DES_LENGTH];
1037
unsigned len = MAX_DES_LENGTH;
1038
1039
// expect EOC
1040
if (!wait_for_eoc(2)) {
1041
goto cmd_bad;
1042
}
1043
1044
len = get_mcu_desc(len, buffer);
1045
cout_word(len);
1046
cout(buffer, len);
1047
}
1048
break;
1049
1050
#ifdef BOOT_DELAY_ADDRESS
1051
1052
case PROTO_SET_DELAY: {
1053
/*
1054
Allow for the bootloader to setup a
1055
boot delay signature which tells the
1056
board to delay for at least a
1057
specified number of seconds on boot.
1058
*/
1059
int v = cin(100);
1060
1061
if (v < 0) {
1062
goto cmd_bad;
1063
}
1064
1065
uint8_t boot_delay = v & 0xFF;
1066
1067
if (boot_delay > BOOT_DELAY_MAX) {
1068
goto cmd_bad;
1069
}
1070
1071
// expect EOC
1072
if (!wait_for_eoc(2)) {
1073
goto cmd_bad;
1074
}
1075
1076
uint32_t sig1 = flash_func_read_word(BOOT_DELAY_ADDRESS);
1077
uint32_t sig2 = flash_func_read_word(BOOT_DELAY_ADDRESS + 4);
1078
1079
if (sig1 != BOOT_DELAY_SIGNATURE1 ||
1080
sig2 != BOOT_DELAY_SIGNATURE2) {
1081
goto cmd_bad;
1082
}
1083
1084
uint32_t value = (BOOT_DELAY_SIGNATURE1 & 0xFFFFFF00) | boot_delay;
1085
flash_func_write_word(BOOT_DELAY_ADDRESS, value);
1086
1087
if (flash_func_read_word(BOOT_DELAY_ADDRESS) != value) {
1088
goto cmd_fail;
1089
}
1090
}
1091
break;
1092
#endif
1093
1094
case PROTO_READ_MULTI: {
1095
arg = cin(50);
1096
if (arg < 0) {
1097
goto cmd_bad;
1098
}
1099
if (arg % 4) {
1100
goto cmd_bad;
1101
}
1102
if ((read_address + arg) > board_info.fw_size) {
1103
goto cmd_bad;
1104
}
1105
// expect EOC
1106
if (!wait_for_eoc(2)) {
1107
goto cmd_bad;
1108
}
1109
arg /= 4;
1110
1111
while (arg-- > 0) {
1112
cout_word(flash_func_read_word(read_address));
1113
read_address += 4;
1114
}
1115
break;
1116
}
1117
1118
// finalise programming and boot the system
1119
//
1120
// command: BOOT/EOC
1121
// reply: INSYNC/OK
1122
//
1123
case PROTO_BOOT:
1124
1125
// expect EOC
1126
if (!wait_for_eoc(1000)) {
1127
goto cmd_bad;
1128
}
1129
1130
if (!flash_write_flush()) {
1131
goto cmd_fail;
1132
}
1133
1134
// program the deferred first word
1135
if (first_words[0] != 0xffffffff) {
1136
#if !BOOT_FROM_EXT_FLASH
1137
if (!flash_write_buffer(0, first_words, RESERVE_LEAD_WORDS)) {
1138
goto cmd_fail;
1139
}
1140
#else
1141
uint32_t programming;
1142
uint32_t delay_us;
1143
uint32_t timeout_us;
1144
if (!ext_flash.start_program_offset(EXT_FLASH_RESERVE_START_KB*1024, (const uint8_t*)first_words, sizeof(first_words), programming, delay_us, timeout_us)) {
1145
// uprintf("ext flash write command failed\n");
1146
goto cmd_fail;
1147
}
1148
uint64_t start_time_us = AP_HAL::micros64();
1149
while (true) {
1150
if (AP_HAL::micros64() > (start_time_us+delay_us)) {
1151
if (!ext_flash.is_device_busy()) {
1152
// uprintf("flash program Successful, elapsed %ld us\n", uint32_t(AP_HAL::micros64() - start_time_us));
1153
break;
1154
} else {
1155
// uprintf("Typical flash program time reached, Still Busy?!\n");
1156
}
1157
}
1158
}
1159
#endif
1160
// revert in case the flash was bad...
1161
memset(first_words, 0xff, sizeof(first_words));
1162
}
1163
1164
// send a sync and wait for it to be collected
1165
sync_response();
1166
delay(100);
1167
1168
// quiesce and jump to the app
1169
return;
1170
1171
case PROTO_DEBUG:
1172
// XXX reserved for ad-hoc debugging as required
1173
break;
1174
1175
case PROTO_SET_BAUD: {
1176
if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {
1177
// prevent timeout going to zero on noise
1178
goto cmd_bad;
1179
}
1180
/* expect arg then EOC */
1181
uint32_t baud = 0;
1182
1183
if (cin_word(&baud, 100)) {
1184
goto cmd_bad;
1185
}
1186
1187
if (!wait_for_eoc(2)) {
1188
goto cmd_bad;
1189
}
1190
1191
// send the sync response for this command
1192
sync_response();
1193
1194
delay(5);
1195
1196
// set the baudrate
1197
port_setbaud(baud);
1198
1199
lock_bl_port();
1200
timeout = 0;
1201
1202
// this is different to what every other case in this
1203
// switch does! Most go through sync_response down the
1204
// bottom, but we need to undertake an action after
1205
// returning the response...
1206
continue;
1207
}
1208
1209
default:
1210
continue;
1211
}
1212
1213
// we got a good command on this port, lock to the port
1214
lock_bl_port();
1215
1216
// once we get both a valid sync and valid get_device then kill
1217
// the timeout
1218
if (done_sync && CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {
1219
timeout = 0;
1220
}
1221
1222
// send the sync response for this command
1223
sync_response();
1224
continue;
1225
cmd_bad:
1226
// if we get a bad command it could be line noise on a
1227
// uart. Set timeout back to original timeout so we don't get
1228
// stuck in the bootloader
1229
if (!done_erase) {
1230
timeout = original_timeout;
1231
}
1232
// send an 'invalid' response but don't kill the timeout - could be garbage
1233
invalid_response();
1234
continue;
1235
1236
cmd_fail:
1237
// send a 'command failed' response but don't kill the timeout - could be garbage
1238
failure_response();
1239
continue;
1240
}
1241
}
1242
1243