HAL_ChibiOS: adjust for changed flash API

This commit is contained in:
Andrew Tridgell 2019-02-04 12:41:45 +11:00
parent 565706cf7e
commit 5201fdf653
2 changed files with 3 additions and 3 deletions

View File

@ -250,7 +250,7 @@ bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *
{
#ifdef STORAGE_FLASH_PAGE
size_t base_address = stm32_flash_getpageaddr(_flash_page+sector);
bool ret = stm32_flash_write(base_address+offset, data, length) == length;
bool ret = stm32_flash_write(base_address+offset, data, length);
if (!ret && _flash_erase_ok()) {
// we are getting flash write errors while disarmed. Try
// re-writing all of flash

View File

@ -262,9 +262,9 @@ bool Util::flash_bootloader()
const uint8_t max_attempts = 10;
for (uint8_t i=0; i<max_attempts; i++) {
void *context = hal.scheduler->disable_interrupts_save();
const int32_t written = stm32_flash_write(addr, fw, fw_size);
bool ok = stm32_flash_write(addr, fw, fw_size);
hal.scheduler->restore_interrupts(context);
if (written == -1 || written < fw_size) {
if (!ok) {
hal.console->printf("Flash failed! (attempt=%u/%u)\n",
i+1,
max_attempts);