mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Bootloader: add support for flashing erasing and verifying ext flash
This commit is contained in:
parent
faedb12493
commit
75bcc76189
@ -43,7 +43,8 @@ extern "C" {
|
|||||||
struct boardinfo board_info = {
|
struct boardinfo board_info = {
|
||||||
.board_type = APJ_BOARD_ID,
|
.board_type = APJ_BOARD_ID,
|
||||||
.board_rev = 0,
|
.board_rev = 0,
|
||||||
.fw_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + FLASH_RESERVE_END_KB + APP_START_OFFSET_KB))*1024
|
.fw_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + FLASH_RESERVE_END_KB + APP_START_OFFSET_KB))*1024,
|
||||||
|
.extf_size = (EXTERNAL_PROG_FLASH_MB * 1024 * 1024)
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifndef HAL_BOOTLOADER_TIMEOUT
|
#ifndef HAL_BOOTLOADER_TIMEOUT
|
||||||
|
@ -125,6 +125,7 @@
|
|||||||
#define PROTO_DEVICE_BOARD_REV 3 // board revision
|
#define PROTO_DEVICE_BOARD_REV 3 // board revision
|
||||||
#define PROTO_DEVICE_FW_SIZE 4 // size of flashable area
|
#define PROTO_DEVICE_FW_SIZE 4 // size of flashable area
|
||||||
#define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10
|
#define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10
|
||||||
|
#define PROTO_DEVICE_EXTF_SIZE 6 // size of available external flash
|
||||||
// all except PROTO_DEVICE_VEC_AREA and PROTO_DEVICE_BOARD_REV should be done
|
// all except PROTO_DEVICE_VEC_AREA and PROTO_DEVICE_BOARD_REV should be done
|
||||||
#define CHECK_GET_DEVICE_FINISHED(x) ((x & (0xB)) == 0xB)
|
#define CHECK_GET_DEVICE_FINISHED(x) ((x & (0xB)) == 0xB)
|
||||||
|
|
||||||
@ -153,6 +154,10 @@ volatile unsigned timer[NTIMERS];
|
|||||||
extern AP_FlashIface_JEDEC ext_flash;
|
extern AP_FlashIface_JEDEC ext_flash;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef BOOT_FROM_EXT_FLASH
|
||||||
|
#define BOOT_FROM_EXT_FLASH 0
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
1ms timer tick callback
|
1ms timer tick callback
|
||||||
*/
|
*/
|
||||||
@ -404,6 +409,7 @@ bootloader(unsigned timeout)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
uint32_t address = board_info.fw_size; /* force erase before upload will work */
|
uint32_t address = board_info.fw_size; /* force erase before upload will work */
|
||||||
|
uint32_t extf_address = board_info.extf_size; /* force erase before upload will work */
|
||||||
uint32_t read_address = 0;
|
uint32_t read_address = 0;
|
||||||
uint32_t first_words[RESERVE_LEAD_WORDS];
|
uint32_t first_words[RESERVE_LEAD_WORDS];
|
||||||
bool done_sync = false;
|
bool done_sync = false;
|
||||||
@ -526,6 +532,10 @@ bootloader(unsigned timeout)
|
|||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case PROTO_DEVICE_EXTF_SIZE:
|
||||||
|
cout((uint8_t *)&board_info.extf_size, sizeof(board_info.extf_size));
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
goto cmd_bad;
|
goto cmd_bad;
|
||||||
}
|
}
|
||||||
@ -643,11 +653,101 @@ bootloader(unsigned timeout)
|
|||||||
erased_bytes += ext_flash.get_sector_size();
|
erased_bytes += ext_flash.get_sector_size();
|
||||||
sector_number++;
|
sector_number++;
|
||||||
}
|
}
|
||||||
|
pct_done = 100;
|
||||||
|
extf_address = 0;
|
||||||
|
cout(&pct_done, sizeof(pct_done));
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
goto cmd_bad;
|
goto cmd_bad;
|
||||||
#endif // EXTERNAL_PROG_FLASH_MB
|
#endif // EXTERNAL_PROG_FLASH_MB
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
// program bytes at current external flash address
|
||||||
|
//
|
||||||
|
// command: PROG_MULTI/<len:1>/<data:len>/EOC
|
||||||
|
// success reply: INSYNC/OK
|
||||||
|
// invalid reply: INSYNC/INVALID
|
||||||
|
// readback failure: INSYNC/FAILURE
|
||||||
|
//
|
||||||
|
case PROTO_EXTF_PROG_MULTI:
|
||||||
|
{
|
||||||
|
if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {
|
||||||
|
// lower chance of random data on a uart triggering erase
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
// expect count
|
||||||
|
led_set(LED_OFF);
|
||||||
|
|
||||||
|
arg = cin(50);
|
||||||
|
|
||||||
|
if (arg < 0) {
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((extf_address + arg) > board_info.extf_size) {
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (arg > sizeof(flash_buffer.c)) {
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i = 0; i < arg; i++) {
|
||||||
|
c = cin(1000);
|
||||||
|
|
||||||
|
if (c < 0) {
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
flash_buffer.c[i] = c;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!wait_for_eoc(200)) {
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if BOOT_FROM_EXT_FLASH
|
||||||
|
// save the first words and don't program it until everything else is done
|
||||||
|
if (extf_address < sizeof(first_words)) {
|
||||||
|
uint8_t n = MIN(sizeof(first_words)-extf_address, arg);
|
||||||
|
memcpy(&first_words[extf_address/4], &flash_buffer.w[0], n);
|
||||||
|
// replace first words with 1 bits we can overwrite later
|
||||||
|
memset(&flash_buffer.w[0], 0xFF, n);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
uint32_t size = arg;
|
||||||
|
uint32_t programming;
|
||||||
|
uint32_t offset = 0;
|
||||||
|
uint32_t delay_us = 0, timeout_us = 0;
|
||||||
|
uint64_t start_time_us;
|
||||||
|
while (true) {
|
||||||
|
if (size == 0) {
|
||||||
|
extf_address += arg;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (!ext_flash.start_program_offset(extf_address+offset, &flash_buffer.c[offset], size, programming, delay_us, timeout_us)) {
|
||||||
|
// uprintf("ext flash write command failed\n");
|
||||||
|
goto cmd_fail;
|
||||||
|
}
|
||||||
|
start_time_us = AP_HAL::micros64();
|
||||||
|
// prepare for next run
|
||||||
|
offset += programming;
|
||||||
|
size -= programming;
|
||||||
|
while (true) {
|
||||||
|
if (AP_HAL::micros64() > (start_time_us+delay_us)) {
|
||||||
|
if (!ext_flash.is_device_busy()) {
|
||||||
|
// uprintf("flash program Successful, elapsed %ld us\n", uint32_t(AP_HAL::micros64() - start_time_us));
|
||||||
|
break;
|
||||||
|
} else {
|
||||||
|
// uprintf("Typical flash program time reached, Still Busy?!\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
// program bytes at current address
|
// program bytes at current address
|
||||||
//
|
//
|
||||||
// command: PROG_MULTI/<len:1>/<data:len>/EOC
|
// command: PROG_MULTI/<len:1>/<data:len>/EOC
|
||||||
@ -746,6 +846,47 @@ bootloader(unsigned timeout)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// fetch CRC of the external flash area
|
||||||
|
//
|
||||||
|
// command: EXTF_GET_CRC/<len:4>/EOC
|
||||||
|
// reply: <crc:4>/INSYNC/OK
|
||||||
|
//
|
||||||
|
case PROTO_EXTF_GET_CRC: {
|
||||||
|
// expect EOC
|
||||||
|
uint32_t cmd_verify_bytes;
|
||||||
|
if (cin_word(&cmd_verify_bytes, 100)) {
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!wait_for_eoc(2)) {
|
||||||
|
goto cmd_bad;
|
||||||
|
}
|
||||||
|
|
||||||
|
// compute CRC of the programmed area
|
||||||
|
uint32_t sum = 0;
|
||||||
|
uint8_t rembytes = cmd_verify_bytes % 4;
|
||||||
|
for (unsigned p = 0; p < (cmd_verify_bytes-rembytes); p+=4) {
|
||||||
|
uint32_t bytes;
|
||||||
|
|
||||||
|
#if BOOT_FROM_EXT_FLASH
|
||||||
|
if (p < sizeof(first_words) && first_words[0] != 0xFFFFFFFF) {
|
||||||
|
bytes = first_words[p/4];
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
ext_flash.read(p, (uint8_t *)&bytes, sizeof(bytes));
|
||||||
|
}
|
||||||
|
sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes));
|
||||||
|
}
|
||||||
|
if (rembytes) {
|
||||||
|
uint8_t bytes[3];
|
||||||
|
ext_flash.read(cmd_verify_bytes-rembytes, bytes, rembytes);
|
||||||
|
sum = crc32_small(sum, bytes, rembytes);
|
||||||
|
}
|
||||||
|
cout_word(sum);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
// read a word from the OTP
|
// read a word from the OTP
|
||||||
//
|
//
|
||||||
// command: GET_OTP/<addr:4>/EOC
|
// command: GET_OTP/<addr:4>/EOC
|
||||||
|
@ -8,6 +8,7 @@ struct boardinfo {
|
|||||||
uint32_t board_type;
|
uint32_t board_type;
|
||||||
uint32_t board_rev;
|
uint32_t board_rev;
|
||||||
uint32_t fw_size;
|
uint32_t fw_size;
|
||||||
|
uint32_t extf_size;
|
||||||
} __attribute__((packed));
|
} __attribute__((packed));
|
||||||
|
|
||||||
extern struct boardinfo board_info;
|
extern struct boardinfo board_info;
|
||||||
|
Loading…
Reference in New Issue
Block a user