mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Bootloader: save a few bytes of flash
This commit is contained in:
parent
855a5d28c0
commit
335ed9ebf1
@ -68,7 +68,9 @@ static BL_Network network;
|
||||
|
||||
int main(void)
|
||||
{
|
||||
#ifdef AP_BOOTLOADER_CUSTOM_HERE4
|
||||
custom_startup();
|
||||
#endif
|
||||
|
||||
flash_init();
|
||||
|
||||
|
@ -750,8 +750,9 @@ bool can_check_update(void)
|
||||
fw_update.reads[i].offset = i*sizeof(uavcan_protocol_file_ReadResponse::data.data);
|
||||
}
|
||||
memcpy(fw_update.path, comms->path, sizeof(uavcan_protocol_file_Path::path.data)+1);
|
||||
memset(comms, 0, sizeof(*comms));
|
||||
ret = true;
|
||||
// clear comms region
|
||||
memset(comms, 0, sizeof(struct app_bootloader_comms));
|
||||
}
|
||||
#endif
|
||||
#if defined(CAN1_BASE) && defined(RCC_APB1ENR_CAN1EN)
|
||||
|
@ -409,7 +409,8 @@ void BL_Network::handle_post(SocketAPM *sock, uint32_t content_length)
|
||||
status_printf("Erasing ...");
|
||||
flash_set_keep_unlocked(true);
|
||||
uint32_t sec=0;
|
||||
while (flash_func_erase_sector(sec)) {
|
||||
while (flash_func_sector_size(sec) != 0 &&
|
||||
flash_func_erase_sector(sec)) {
|
||||
thread_sleep_ms(10);
|
||||
sec++;
|
||||
if (stm32_flash_getpageaddr(sec) - stm32_flash_getpageaddr(0) >= content_length) {
|
||||
|
@ -150,9 +150,6 @@ bool flash_func_is_erased(uint32_t sector)
|
||||
|
||||
bool flash_func_erase_sector(uint32_t sector, bool force_erase)
|
||||
{
|
||||
if (sector >= num_pages) {
|
||||
return false;
|
||||
}
|
||||
#if AP_BOOTLOADER_ALWAYS_ERASE
|
||||
return stm32_flash_erasepage(flash_base_page+sector);
|
||||
#else
|
||||
|
Loading…
Reference in New Issue
Block a user