HAL_PX4: update for new AP_FlashStorage API

allow flash sector erase while disarmed
This commit is contained in:
Andrew Tridgell 2016-11-19 11:29:43 +11:00
parent bfd137e36a
commit 6bc0c76d54
2 changed files with 14 additions and 2 deletions

View File

@ -234,7 +234,7 @@ void PX4Storage::_flash_write(uint16_t line)
{
if (_flash.write(line*PX4_STORAGE_LINE_SIZE, PX4_STORAGE_LINE_SIZE)) {
// mark the line clean
_dirty_mask.clear(line);
_dirty_mask.clear(line);
} else {
perf_count(_perf_errors);
}
@ -268,4 +268,13 @@ bool PX4Storage::_flash_erase_sector(uint8_t sector)
return up_progmem_erasepage(_flash_page+sector) > 0;
}
/*
callback to check if erase is allowed
*/
bool PX4Storage::_flash_erase_ok(void)
{
// only allow erase while disarmed
return !hal.util->get_soft_armed();
}
#endif // CONFIG_HAL_BOARD

View File

@ -52,13 +52,16 @@ private:
bool _flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length);
bool _flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length);
bool _flash_erase_sector(uint8_t sector);
bool _flash_erase_ok(void);
uint8_t _flash_page;
bool _flash_failed;
AP_FlashStorage _flash{_buffer,
128*1024U,
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_write_data, bool, uint8_t, uint32_t, const uint8_t *, uint16_t),
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_read_data, bool, uint8_t, uint32_t, uint8_t *, uint16_t),
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_erase_sector, bool, uint8_t)};
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_erase_sector, bool, uint8_t),
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_erase_ok, bool)};
void _flash_load(void);
void _flash_write(uint16_t line);