mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
DataFlash: removed the byte and word based interfaces
simplifing ready for PX4 flash logging
This commit is contained in:
parent
74439b4f17
commit
20825cc903
@ -64,21 +64,6 @@ void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size)
|
||||
}
|
||||
|
||||
|
||||
void DataFlash_Class::WriteByte(uint8_t data)
|
||||
{
|
||||
WriteBlock(&data, sizeof(data));
|
||||
}
|
||||
|
||||
void DataFlash_Class::WriteInt(int16_t data)
|
||||
{
|
||||
WriteBlock(&data, sizeof(data));
|
||||
}
|
||||
|
||||
void DataFlash_Class::WriteLong(int32_t data)
|
||||
{
|
||||
WriteBlock(&data, sizeof(data));
|
||||
}
|
||||
|
||||
// Get the last page written to
|
||||
int16_t DataFlash_Class::GetWritePage()
|
||||
{
|
||||
@ -143,27 +128,6 @@ void DataFlash_Class::ReadBlock(void *pBuffer, uint16_t size)
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t DataFlash_Class::ReadByte()
|
||||
{
|
||||
uint8_t result = 0;
|
||||
ReadBlock(&result, sizeof(result));
|
||||
return result;
|
||||
}
|
||||
|
||||
int16_t DataFlash_Class::ReadInt()
|
||||
{
|
||||
int16_t result;
|
||||
ReadBlock(&result, sizeof(result));
|
||||
return result;
|
||||
}
|
||||
|
||||
int32_t DataFlash_Class::ReadLong()
|
||||
{
|
||||
int32_t result;
|
||||
ReadBlock(&result, sizeof(result));
|
||||
return result;
|
||||
}
|
||||
|
||||
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
|
||||
{
|
||||
df_FileNumber = FileNumber;
|
||||
@ -190,7 +154,8 @@ void DataFlash_Class::EraseAll()
|
||||
}
|
||||
// write the logging format in the last page
|
||||
StartWrite(df_NumPages+1);
|
||||
WriteLong(DF_LOGGING_FORMAT);
|
||||
uint32_t version = DF_LOGGING_FORMAT;
|
||||
WriteBlock(&version, sizeof(version));
|
||||
FinishWrite();
|
||||
}
|
||||
|
||||
@ -199,7 +164,9 @@ void DataFlash_Class::EraseAll()
|
||||
*/
|
||||
bool DataFlash_Class::NeedErase(void)
|
||||
{
|
||||
uint32_t version;
|
||||
StartRead(df_NumPages+1);
|
||||
return ReadLong() != DF_LOGGING_FORMAT;
|
||||
ReadBlock(&version, sizeof(version));
|
||||
return version != DF_LOGGING_FORMAT;
|
||||
}
|
||||
|
||||
|
@ -77,17 +77,11 @@ public:
|
||||
void StartWrite(int16_t PageAdr);
|
||||
void FinishWrite(void);
|
||||
void WriteBlock(const void *pBuffer, uint16_t size);
|
||||
void WriteByte(uint8_t data);
|
||||
void WriteInt(int16_t data);
|
||||
void WriteLong(int32_t data);
|
||||
|
||||
|
||||
// Read methods
|
||||
void StartRead(int16_t PageAdr);
|
||||
void ReadBlock(void *pBuffer, uint16_t size);
|
||||
uint8_t ReadByte();
|
||||
int16_t ReadInt();
|
||||
int32_t ReadLong();
|
||||
|
||||
// file numbers
|
||||
void SetFileNumber(uint16_t FileNumber);
|
||||
@ -111,6 +105,7 @@ public:
|
||||
void start_new_log(void);
|
||||
uint16_t log_read_process(uint16_t start_page, uint16_t end_page,
|
||||
void (*callback)(uint8_t msgid));
|
||||
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||
|
||||
/*
|
||||
every logged packet starts with 3 bytes
|
||||
|
@ -18,15 +18,9 @@
|
||||
* Methods:
|
||||
* Init() : Library initialization (SPI initialization)
|
||||
* StartWrite(page) : Start a write session. page=start page.
|
||||
* WriteByte(data) : Write a byte
|
||||
* WriteInt(data) : Write an integer (2 bytes)
|
||||
* WriteLong(data) : Write a long (4 bytes)
|
||||
* StartRead(page) : Start a read on (page)
|
||||
* GetWritePage() : Returns the last page written to
|
||||
* GetPage() : Returns the last page read
|
||||
* ReadByte()
|
||||
* ReadInt()
|
||||
* ReadLong()
|
||||
*
|
||||
* Properties:
|
||||
*
|
||||
|
@ -18,15 +18,9 @@
|
||||
* Methods:
|
||||
* Init() : Library initialization (SPI initialization)
|
||||
* StartWrite(page) : Start a write session. page=start page.
|
||||
* WriteByte(data) : Write a byte
|
||||
* WriteInt(data) : Write an integer (2 bytes)
|
||||
* WriteLong(data) : Write a long (4 bytes)
|
||||
* StartRead(page) : Start a read on (page)
|
||||
* GetWritePage() : Returns the last page written to
|
||||
* GetPage() : Returns the last page read
|
||||
* ReadByte()
|
||||
* ReadInt()
|
||||
* ReadLong()
|
||||
*
|
||||
* Properties:
|
||||
*
|
||||
|
@ -239,7 +239,8 @@ uint16_t DataFlash_Class::log_read_process(uint16_t start_page, uint16_t end_pag
|
||||
StartRead(start_page);
|
||||
|
||||
while (true) {
|
||||
uint8_t data = ReadByte();
|
||||
uint8_t data;
|
||||
ReadBlock(&data, 1);
|
||||
|
||||
// This is a state machine to read the packets
|
||||
switch(log_step) {
|
||||
@ -265,10 +266,26 @@ uint16_t DataFlash_Class::log_read_process(uint16_t start_page, uint16_t end_pag
|
||||
}
|
||||
uint16_t new_page = GetPage();
|
||||
if (new_page != page) {
|
||||
if (new_page == end_page) break;
|
||||
if (new_page == end_page) {
|
||||
return packet_count;
|
||||
}
|
||||
page = new_page;
|
||||
}
|
||||
}
|
||||
|
||||
return packet_count;
|
||||
}
|
||||
|
||||
/*
|
||||
dump header information from all log pages
|
||||
*/
|
||||
void DataFlash_Class::DumpPageInfo(AP_HAL::BetterStream *port)
|
||||
{
|
||||
for (uint16_t count=1; count<=df_NumPages; count++) {
|
||||
StartRead(count);
|
||||
port->printf_P(PSTR("DF page, log file #, log page: %u,\t"), (unsigned)count);
|
||||
port->printf_P(PSTR("%u,\t"), (unsigned)GetFileNumber());
|
||||
port->printf_P(PSTR("%u\n"), (unsigned)GetFilePage());
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user