Browse Source

HAL_ChibiOS: improve error messages for flashing bootloader

send progress as statustext messages
zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
1540cf958b
  1. 23
      libraries/AP_HAL_ChibiOS/Util.cpp

23
libraries/AP_HAL_ChibiOS/Util.cpp

@ -165,6 +165,13 @@ uint64_t Util::get_hw_rtc() const
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT) #if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
#if defined(HAL_NO_GCS) || defined(HAL_BOOTLOADER_BUILD)
#define Debug(fmt, args ...) do { hal.console->printf(fmt, ## args); } while (0)
#else
#include <GCS_MAVLink/GCS.h>
#define Debug(fmt, args ...) do { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } while (0)
#endif
Util::FlashBootloader Util::flash_bootloader() Util::FlashBootloader Util::flash_bootloader()
{ {
uint32_t fw_size; uint32_t fw_size;
@ -174,7 +181,7 @@ Util::FlashBootloader Util::flash_bootloader()
const uint8_t *fw = AP_ROMFS::find_decompress(fw_name, fw_size); const uint8_t *fw = AP_ROMFS::find_decompress(fw_name, fw_size);
if (!fw) { if (!fw) {
hal.console->printf("failed to find %s\n", fw_name); Debug("failed to find %s\n", fw_name);
return FlashBootloader::NOT_AVAILABLE; return FlashBootloader::NOT_AVAILABLE;
} }
// make sure size is multiple of 32 // make sure size is multiple of 32
@ -182,12 +189,12 @@ Util::FlashBootloader Util::flash_bootloader()
const uint32_t addr = hal.flash->getpageaddr(0); const uint32_t addr = hal.flash->getpageaddr(0);
if (!memcmp(fw, (const void*)addr, fw_size)) { if (!memcmp(fw, (const void*)addr, fw_size)) {
hal.console->printf("Bootloader up-to-date\n"); Debug("Bootloader up-to-date\n");
AP_ROMFS::free(fw); AP_ROMFS::free(fw);
return FlashBootloader::NO_CHANGE; return FlashBootloader::NO_CHANGE;
} }
hal.console->printf("Erasing\n"); Debug("Erasing\n");
uint32_t erased_size = 0; uint32_t erased_size = 0;
uint8_t erase_page = 0; uint8_t erase_page = 0;
while (erased_size < fw_size) { while (erased_size < fw_size) {
@ -198,7 +205,7 @@ Util::FlashBootloader Util::flash_bootloader()
} }
hal.scheduler->expect_delay_ms(1000); hal.scheduler->expect_delay_ms(1000);
if (!hal.flash->erasepage(erase_page)) { if (!hal.flash->erasepage(erase_page)) {
hal.console->printf("Erase %u failed\n", erase_page); Debug("Erase %u failed\n", erase_page);
AP_ROMFS::free(fw); AP_ROMFS::free(fw);
return FlashBootloader::FAIL; return FlashBootloader::FAIL;
} }
@ -206,27 +213,27 @@ Util::FlashBootloader Util::flash_bootloader()
erase_page++; erase_page++;
} }
hal.console->printf("Flashing %s @%08x\n", fw_name, (unsigned int)addr); Debug("Flashing %s @%08x\n", fw_name, (unsigned int)addr);
const uint8_t max_attempts = 10; const uint8_t max_attempts = 10;
hal.flash->keep_unlocked(true); hal.flash->keep_unlocked(true);
for (uint8_t i=0; i<max_attempts; i++) { for (uint8_t i=0; i<max_attempts; i++) {
hal.scheduler->expect_delay_ms(1000); hal.scheduler->expect_delay_ms(1000);
bool ok = hal.flash->write(addr, fw, fw_size); bool ok = hal.flash->write(addr, fw, fw_size);
if (!ok) { if (!ok) {
hal.console->printf("Flash failed! (attempt=%u/%u)\n", Debug("Flash failed! (attempt=%u/%u)\n",
i+1, i+1,
max_attempts); max_attempts);
hal.scheduler->delay(100); hal.scheduler->delay(100);
continue; continue;
} }
hal.console->printf("Flash OK\n"); Debug("Flash OK\n");
hal.flash->keep_unlocked(false); hal.flash->keep_unlocked(false);
AP_ROMFS::free(fw); AP_ROMFS::free(fw);
return FlashBootloader::OK; return FlashBootloader::OK;
} }
hal.flash->keep_unlocked(false); hal.flash->keep_unlocked(false);
hal.console->printf("Flash failed after %u attempts\n", max_attempts); Debug("Flash failed after %u attempts\n", max_attempts);
AP_ROMFS::free(fw); AP_ROMFS::free(fw);
return FlashBootloader::FAIL; return FlashBootloader::FAIL;
} }

Loading…
Cancel
Save