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