mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
HAL_ChibiOS: fixed multi-page bootloader update
and use new enum
This commit is contained in:
parent
9a778418a5
commit
81325ab14d
@ -226,7 +226,7 @@ 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)
|
||||||
|
|
||||||
bool Util::flash_bootloader()
|
Util::FlashBootloader Util::flash_bootloader()
|
||||||
{
|
{
|
||||||
uint32_t fw_size;
|
uint32_t fw_size;
|
||||||
const char *fw_name = "bootloader.bin";
|
const char *fw_name = "bootloader.bin";
|
||||||
@ -236,22 +236,34 @@ bool 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);
|
hal.console->printf("failed to find %s\n", fw_name);
|
||||||
return false;
|
return FlashBootloader::NOT_AVAILABLE;
|
||||||
}
|
}
|
||||||
|
|
||||||
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");
|
hal.console->printf("Bootloader up-to-date\n");
|
||||||
AP_ROMFS::free(fw);
|
AP_ROMFS::free(fw);
|
||||||
return true;
|
return FlashBootloader::NO_CHANGE;
|
||||||
}
|
}
|
||||||
|
|
||||||
hal.console->printf("Erasing\n");
|
hal.console->printf("Erasing\n");
|
||||||
if (!hal.flash->erasepage(0)) {
|
uint32_t erased_size = 0;
|
||||||
hal.console->printf("Erase failed\n");
|
uint8_t erase_page = 0;
|
||||||
AP_ROMFS::free(fw);
|
while (erased_size < fw_size) {
|
||||||
return false;
|
if (!hal.flash->erasepage(erase_page)) {
|
||||||
|
hal.console->printf("Erase %u failed\n", erase_page);
|
||||||
|
AP_ROMFS::free(fw);
|
||||||
|
return FlashBootloader::FAIL;
|
||||||
|
}
|
||||||
|
uint32_t page_size = hal.flash->getpagesize(erase_page);
|
||||||
|
if (page_size == 0) {
|
||||||
|
AP_ROMFS::free(fw);
|
||||||
|
return FlashBootloader::FAIL;
|
||||||
|
}
|
||||||
|
erased_size += page_size;
|
||||||
|
erase_page++;
|
||||||
}
|
}
|
||||||
|
|
||||||
hal.console->printf("Flashing %s @%08x\n", fw_name, (unsigned int)addr);
|
hal.console->printf("Flashing %s @%08x\n", fw_name, (unsigned int)addr);
|
||||||
const uint8_t max_attempts = 10;
|
const uint8_t max_attempts = 10;
|
||||||
for (uint8_t i=0; i<max_attempts; i++) {
|
for (uint8_t i=0; i<max_attempts; i++) {
|
||||||
@ -265,12 +277,12 @@ bool Util::flash_bootloader()
|
|||||||
}
|
}
|
||||||
hal.console->printf("Flash OK\n");
|
hal.console->printf("Flash OK\n");
|
||||||
AP_ROMFS::free(fw);
|
AP_ROMFS::free(fw);
|
||||||
return true;
|
return FlashBootloader::OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
hal.console->printf("Flash failed after %u attempts\n", max_attempts);
|
hal.console->printf("Flash failed after %u attempts\n", max_attempts);
|
||||||
AP_ROMFS::free(fw);
|
AP_ROMFS::free(fw);
|
||||||
return false;
|
return FlashBootloader::FAIL;
|
||||||
}
|
}
|
||||||
#endif // !HAL_NO_FLASH_SUPPORT && !HAL_NO_ROMFS_SUPPORT
|
#endif // !HAL_NO_FLASH_SUPPORT && !HAL_NO_ROMFS_SUPPORT
|
||||||
|
|
||||||
|
@ -100,7 +100,7 @@ private:
|
|||||||
*/
|
*/
|
||||||
uint64_t get_hw_rtc() const override;
|
uint64_t get_hw_rtc() const override;
|
||||||
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
|
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
|
||||||
bool flash_bootloader() override;
|
FlashBootloader flash_bootloader() override;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef ENABLE_HEAP
|
#ifdef ENABLE_HEAP
|
||||||
|
Loading…
Reference in New Issue
Block a user