mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed merge errors with hal.flash usage
This commit is contained in:
parent
0e3183b3cf
commit
c1000cfe2a
|
@ -11,20 +11,20 @@ public:
|
|||
uint32_t getpagesize(uint32_t page) override { return stm32_flash_getpagesize(page); }
|
||||
uint32_t getnumpages(void) override { return stm32_flash_getnumpages(); }
|
||||
bool erasepage(uint32_t page) override {
|
||||
chMtxLock(&sem);
|
||||
sem.take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||
bool ret = stm32_flash_erasepage(page);
|
||||
chMtxUnlock(&sem);
|
||||
sem.give();
|
||||
return ret;
|
||||
}
|
||||
bool write(uint32_t addr, const void *buf, uint32_t count) override {
|
||||
chMtxLock(&sem);
|
||||
sem.take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||
bool ret = (stm32_flash_write(addr, buf, count) == count);
|
||||
chMtxUnlock(&sem);
|
||||
sem.give();
|
||||
return ret;
|
||||
}
|
||||
void keep_unlocked(bool set) override { stm32_flash_keep_unlocked(set); }
|
||||
bool ispageerased(uint32_t page) override { return stm32_flash_ispageerased(page); }
|
||||
|
||||
private:
|
||||
mutex_t sem;
|
||||
Semaphore sem;
|
||||
};
|
||||
|
|
|
@ -269,7 +269,7 @@ bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *
|
|||
(unsigned)sector, (unsigned)offset, (unsigned)length, (unsigned)ok);
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
return false;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
|
|
|
@ -63,7 +63,7 @@ private:
|
|||
|
||||
#ifdef STORAGE_FLASH_PAGE
|
||||
AP_FlashStorage _flash{_buffer,
|
||||
hal.flash->getpagesize(STORAGE_FLASH_PAGE),
|
||||
stm32_flash_getpagesize(STORAGE_FLASH_PAGE),
|
||||
FUNCTOR_BIND_MEMBER(&Storage::_flash_write_data, bool, uint8_t, uint32_t, const uint8_t *, uint16_t),
|
||||
FUNCTOR_BIND_MEMBER(&Storage::_flash_read_data, bool, uint8_t, uint32_t, uint8_t *, uint16_t),
|
||||
FUNCTOR_BIND_MEMBER(&Storage::_flash_erase_sector, bool, uint8_t),
|
||||
|
|
|
@ -216,10 +216,8 @@ bool Util::flash_bootloader()
|
|||
hal.console->printf("Flashing %s @%08x\n", fw_name, (unsigned int)addr);
|
||||
const uint8_t max_attempts = 10;
|
||||
for (uint8_t i=0; i<max_attempts; i++) {
|
||||
void *context = hal.scheduler->disable_interrupts_save();
|
||||
bool ok = hal.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