mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
DataFlash: hopefully fixed cause of frequent dataflash erase
Wait for 0.1s after erase and before we start writing parameters to the log Pair-Programmed-With: Randy Mackay <rmackay9@yahoo.com>
This commit is contained in:
parent
7fdf1b6f78
commit
095505129c
@ -13,13 +13,6 @@
|
|||||||
#include <AP_AHRS.h>
|
#include <AP_AHRS.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
// the last page holds the log format in first 4 bytes. Please change
|
|
||||||
// this if (and only if!) the low level format changes
|
|
||||||
#define DF_LOGGING_FORMAT 0x28122013
|
|
||||||
|
|
||||||
// we use an invalie logging format to test the chip erase
|
|
||||||
#define DF_LOGGING_FORMAT_INVALID 0x28122012
|
|
||||||
|
|
||||||
class DataFlash_Class
|
class DataFlash_Class
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
@ -8,6 +8,10 @@
|
|||||||
|
|
||||||
extern AP_HAL::HAL& hal;
|
extern AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
// the last page holds the log format in first 4 bytes. Please change
|
||||||
|
// this if (and only if!) the low level format changes
|
||||||
|
#define DF_LOGGING_FORMAT 0x28122013
|
||||||
|
|
||||||
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
||||||
void DataFlash_Block::StartWrite(uint16_t PageAdr)
|
void DataFlash_Block::StartWrite(uint16_t PageAdr)
|
||||||
{
|
{
|
||||||
@ -149,17 +153,19 @@ uint16_t DataFlash_Block::GetFilePage()
|
|||||||
|
|
||||||
void DataFlash_Block::EraseAll()
|
void DataFlash_Block::EraseAll()
|
||||||
{
|
{
|
||||||
for(uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
|
for (uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
|
||||||
BlockErase(j);
|
BlockErase(j);
|
||||||
if (j%6 == 0) {
|
if (j%6 == 0) {
|
||||||
hal.scheduler->delay(6);
|
hal.scheduler->delay(6);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// write the logging format in the last page
|
// write the logging format in the last page
|
||||||
|
hal.scheduler->delay(100);
|
||||||
StartWrite(df_NumPages+1);
|
StartWrite(df_NumPages+1);
|
||||||
uint32_t version = DF_LOGGING_FORMAT;
|
uint32_t version = DF_LOGGING_FORMAT;
|
||||||
WriteBlock(&version, sizeof(version));
|
WriteBlock(&version, sizeof(version));
|
||||||
FinishWrite();
|
FinishWrite();
|
||||||
|
hal.scheduler->delay(100);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -172,5 +178,3 @@ bool DataFlash_Block::NeedErase(void)
|
|||||||
ReadBlock(&version, sizeof(version));
|
ReadBlock(&version, sizeof(version));
|
||||||
return version != DF_LOGGING_FORMAT;
|
return version != DF_LOGGING_FORMAT;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -9,13 +9,6 @@
|
|||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
// the last page holds the log format in first 4 bytes. Please change
|
|
||||||
// this if (and only if!) the low level format changes
|
|
||||||
#define DF_LOGGING_FORMAT 0x28122013
|
|
||||||
|
|
||||||
// we use an invalie logging format to test the chip erase
|
|
||||||
#define DF_LOGGING_FORMAT_INVALID 0x28122012
|
|
||||||
|
|
||||||
class DataFlash_Block : public DataFlash_Class
|
class DataFlash_Block : public DataFlash_Class
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
Loading…
Reference in New Issue
Block a user