mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: adjust for changed flash API
This commit is contained in:
parent
565706cf7e
commit
5201fdf653
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue