mirror of https://github.com/ArduPilot/ardupilot
DataFlash: AP_HAL port fixups
This commit is contained in:
parent
a14621534c
commit
7b9b088261
|
@ -4,8 +4,10 @@
|
|||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <AP_HAL.h>
|
||||
#include "DataFlash.h"
|
||||
|
||||
extern AP_HAL::HAL& hal;
|
||||
|
||||
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
||||
void DataFlash_Class::StartWrite(int16_t PageAdr)
|
||||
|
@ -186,11 +188,13 @@ uint16_t DataFlash_Class::GetFilePage()
|
|||
return df_FilePage;
|
||||
}
|
||||
|
||||
void DataFlash_Class::EraseAll(void (*delay_cb)(unsigned long))
|
||||
void DataFlash_Class::EraseAll()
|
||||
{
|
||||
for(uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
|
||||
BlockErase(j);
|
||||
delay_cb(1);
|
||||
if (j%6 == 0) {
|
||||
hal.scheduler->delay(6);
|
||||
}
|
||||
}
|
||||
// write the logging format in the last page
|
||||
StartWrite(df_NumPages+1);
|
||||
|
|
|
@ -59,7 +59,7 @@ public:
|
|||
int16_t GetWritePage(void);
|
||||
|
||||
// erase handling
|
||||
void EraseAll(void (*delay_cb)(unsigned long));
|
||||
void EraseAll();
|
||||
bool NeedErase(void);
|
||||
|
||||
// Write methods
|
||||
|
|
Loading…
Reference in New Issue