mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: make flashing a bit faster
This commit is contained in:
parent
dd1bd43a2e
commit
4fbd1e409f
|
@ -212,6 +212,8 @@ jump_to_app()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
flash_set_keep_unlocked(false);
|
||||||
|
|
||||||
led_set(LED_OFF);
|
led_set(LED_OFF);
|
||||||
|
|
||||||
/* kill the systick timer */
|
/* kill the systick timer */
|
||||||
|
@ -296,28 +298,6 @@ cout_word(uint32_t val)
|
||||||
cout((uint8_t *)&val, 4);
|
cout((uint8_t *)&val, 4);
|
||||||
}
|
}
|
||||||
|
|
||||||
static int
|
|
||||||
cin_word(uint32_t *wp, unsigned timeout)
|
|
||||||
{
|
|
||||||
union {
|
|
||||||
uint32_t w;
|
|
||||||
uint8_t b[4];
|
|
||||||
} u;
|
|
||||||
|
|
||||||
for (unsigned i = 0; i < 4; i++) {
|
|
||||||
int c = cin(timeout);
|
|
||||||
|
|
||||||
if (c < 0) {
|
|
||||||
return c;
|
|
||||||
}
|
|
||||||
|
|
||||||
u.b[i] = c & 0xff;
|
|
||||||
}
|
|
||||||
|
|
||||||
*wp = u.w;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint32_t
|
static uint32_t
|
||||||
crc32(const uint8_t *src, unsigned len, unsigned state)
|
crc32(const uint8_t *src, unsigned len, unsigned state)
|
||||||
{
|
{
|
||||||
|
@ -476,6 +456,8 @@ bootloader(unsigned timeout)
|
||||||
goto cmd_bad;
|
goto cmd_bad;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
flash_set_keep_unlocked(true);
|
||||||
|
|
||||||
// clear the bootloader LED while erasing - it stops blinking at random
|
// clear the bootloader LED while erasing - it stops blinking at random
|
||||||
// and that's confusing
|
// and that's confusing
|
||||||
led_set(LED_OFF);
|
led_set(LED_OFF);
|
||||||
|
@ -553,7 +535,6 @@ bootloader(unsigned timeout)
|
||||||
}
|
}
|
||||||
|
|
||||||
arg /= 4;
|
arg /= 4;
|
||||||
|
|
||||||
for (int i = 0; i < arg; i++) {
|
for (int i = 0; i < arg; i++) {
|
||||||
// program the word
|
// program the word
|
||||||
flash_func_write_word(address, flash_buffer.w[i]);
|
flash_func_write_word(address, flash_buffer.w[i]);
|
||||||
|
|
|
@ -17,12 +17,22 @@ int16_t cin(unsigned timeout_ms)
|
||||||
{
|
{
|
||||||
uint8_t b = 0;
|
uint8_t b = 0;
|
||||||
if (chnReadTimeout(&SDU1, &b, 1, MS2ST(timeout_ms)) != 1) {
|
if (chnReadTimeout(&SDU1, &b, 1, MS2ST(timeout_ms)) != 1) {
|
||||||
chThdSleepMilliseconds(1);
|
chThdSleepMicroseconds(100);
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
return b;
|
return b;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int cin_word(uint32_t *wp, unsigned timeout_ms)
|
||||||
|
{
|
||||||
|
if (chnReadTimeout(&SDU1, (uint8_t *)wp, 4, MS2ST(timeout_ms)) != 4) {
|
||||||
|
chThdSleepMicroseconds(100);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void cout(uint8_t *data, uint32_t len)
|
void cout(uint8_t *data, uint32_t len)
|
||||||
{
|
{
|
||||||
chnWriteTimeout(&SDU1, data, len, MS2ST(100));
|
chnWriteTimeout(&SDU1, data, len, MS2ST(100));
|
||||||
|
@ -51,6 +61,10 @@ void flash_init(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void flash_set_keep_unlocked(bool set)
|
||||||
|
{
|
||||||
|
stm32_flash_keep_unlocked(set);
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
read a word at offset relative to FLASH_BOOTLOADER_LOAD_KB
|
read a word at offset relative to FLASH_BOOTLOADER_LOAD_KB
|
||||||
|
|
|
@ -13,6 +13,7 @@ struct boardinfo {
|
||||||
extern struct boardinfo board_info;
|
extern struct boardinfo board_info;
|
||||||
|
|
||||||
int16_t cin(unsigned timeout_ms);
|
int16_t cin(unsigned timeout_ms);
|
||||||
|
int cin_word(uint32_t *wp, unsigned timeout_ms);
|
||||||
void cout(uint8_t *data, uint32_t len);
|
void cout(uint8_t *data, uint32_t len);
|
||||||
void cfini(void);
|
void cfini(void);
|
||||||
|
|
||||||
|
@ -24,6 +25,7 @@ uint32_t flash_func_sector_size(uint32_t sector);
|
||||||
void flash_func_erase_sector(uint32_t sector);
|
void flash_func_erase_sector(uint32_t sector);
|
||||||
uint32_t flash_func_read_otp(uint32_t idx);
|
uint32_t flash_func_read_otp(uint32_t idx);
|
||||||
uint32_t flash_func_read_sn(uint32_t idx);
|
uint32_t flash_func_read_sn(uint32_t idx);
|
||||||
|
void flash_set_keep_unlocked(bool);
|
||||||
|
|
||||||
uint32_t get_mcu_id(void);
|
uint32_t get_mcu_id(void);
|
||||||
uint32_t get_mcu_desc(uint32_t len, uint8_t *buf);
|
uint32_t get_mcu_desc(uint32_t len, uint8_t *buf);
|
||||||
|
|
Loading…
Reference in New Issue