mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_FlashStorage: fixed build of example on small memory boards
This commit is contained in:
parent
d2446e1219
commit
985a319c42
@ -22,7 +22,7 @@ private:
|
|||||||
uint8_t mem_mirror[AP_FlashStorage::storage_size];
|
uint8_t mem_mirror[AP_FlashStorage::storage_size];
|
||||||
|
|
||||||
// flash buffer
|
// flash buffer
|
||||||
uint8_t flash[2][flash_sector_size];
|
uint8_t *flash[2];
|
||||||
|
|
||||||
bool flash_write(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length);
|
bool flash_write(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length);
|
||||||
bool flash_read(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length);
|
bool flash_read(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length);
|
||||||
@ -105,6 +105,8 @@ void FlashTest::write(uint16_t offset, const uint8_t *data, uint16_t length)
|
|||||||
*/
|
*/
|
||||||
void FlashTest::setup(void)
|
void FlashTest::setup(void)
|
||||||
{
|
{
|
||||||
|
flash[0] = (uint8_t *)malloc(flash_sector_size);
|
||||||
|
flash[1] = (uint8_t *)malloc(flash_sector_size);
|
||||||
flash_erase(0);
|
flash_erase(0);
|
||||||
flash_erase(1);
|
flash_erase(1);
|
||||||
hal.console->printf("AP_FlashStorage test\n");
|
hal.console->printf("AP_FlashStorage test\n");
|
||||||
|
Loading…
Reference in New Issue
Block a user