HAL_ChibiOS: use hal.flash API

This commit is contained in:
Andrew Tridgell 2019-03-26 11:21:53 +11:00
parent 7a70a888b5
commit 7c726b2f42
4 changed files with 32 additions and 8 deletions

View File

@ -0,0 +1,24 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_ChibiOS_Namespace.h"
#include <AP_Common/Semaphore.h>
#include "hwdef/common/flash.h"
class ChibiOS::Flash : public AP_HAL::Flash {
public:
uint32_t getpageaddr(uint32_t page) override { return stm32_flash_getpageaddr(page); }
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 {
WITH_SEMAPHORE(sem);
return stm32_flash_erasepage(page); }
bool write(uint32_t addr, const void *buf, uint32_t count) override {
WITH_SEMAPHORE(sem);
return stm32_flash_write(addr, buf, count); }
void keep_unlocked(bool set) override { stm32_flash_keep_unlocked(set); }
bool ispageerased(uint32_t page) override { return stm32_flash_ispageerased(page); }
private:
HAL_Semaphore sem;
};

View File

@ -251,9 +251,9 @@ void Storage::_flash_write(uint16_t line)
bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
{
#ifdef STORAGE_FLASH_PAGE
size_t base_address = stm32_flash_getpageaddr(_flash_page+sector);
size_t base_address = hal.flash->getpageaddr(_flash_page+sector);
for (uint8_t i=0; i<STORAGE_FLASH_RETRIES; i++) {
if (stm32_flash_write(base_address+offset, data, length)) {
if (hal.flash->write(base_address+offset, data, length)) {
return true;
}
hal.scheduler->delay(1);
@ -280,7 +280,7 @@ bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *
*/
bool Storage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
{
size_t base_address = stm32_flash_getpageaddr(_flash_page+sector);
size_t base_address = hal.flash->getpageaddr(_flash_page+sector);
const uint8_t *b = ((const uint8_t *)base_address)+offset;
memcpy(data, b, length);
return true;
@ -292,7 +292,7 @@ bool Storage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, u
bool Storage::_flash_erase_sector(uint8_t sector)
{
for (uint8_t i=0; i<STORAGE_FLASH_RETRIES; i++) {
if (stm32_flash_erasepage(_flash_page+sector)) {
if (hal.flash->erasepage(_flash_page+sector)) {
return true;
}
hal.scheduler->delay(1);

View File

@ -63,7 +63,7 @@ private:
#ifdef STORAGE_FLASH_PAGE
AP_FlashStorage _flash{_buffer,
stm32_flash_getpagesize(STORAGE_FLASH_PAGE),
hal.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),

View File

@ -235,7 +235,7 @@ bool Util::flash_bootloader()
return false;
}
const uint32_t addr = stm32_flash_getpageaddr(0);
const uint32_t addr = hal.flash->getpageaddr(0);
if (!memcmp(fw, (const void*)addr, fw_size)) {
hal.console->printf("Bootloader up-to-date\n");
free(fw);
@ -243,7 +243,7 @@ bool Util::flash_bootloader()
}
hal.console->printf("Erasing\n");
if (!stm32_flash_erasepage(0)) {
if (!hal.flash->erasepage(0)) {
hal.console->printf("Erase failed\n");
free(fw);
return false;
@ -252,7 +252,7 @@ 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();
bool ok = stm32_flash_write(addr, fw, fw_size);
bool ok = hal.flash->write(addr, fw, fw_size);
hal.scheduler->restore_interrupts(context);
if (!ok) {
hal.console->printf("Flash failed! (attempt=%u/%u)\n",