Change to logging file system.

This commit is somewhat temporary as I have come up with a better scheme and will be modifying this.  Just making this commit in case I need to roll back
This commit is contained in:
Doug Weibel 2011-11-16 08:29:40 -07:00
parent 7f2ec90703
commit a11ea12ca8
6 changed files with 303 additions and 158 deletions

View File

@ -450,7 +450,9 @@ void loop()
if (millis() - perf_mon_timer > 20000) {
if (mainLoop_count != 0) {
if (g.log_bitmask & MASK_LOG_PM)
#if HIL_MODE != HIL_MODE_ATTITUDE
Log_Write_Performance();
#endif
resetPerfData();
}

View File

@ -53,7 +53,9 @@ print_log_menu(void)
{
int log_start;
int log_end;
byte last_log_num = get_num_logs();
int temp;
uint16_t num_logs = get_num_logs();
//Serial.print("num logs: "); Serial.println(num_logs, DEC);
Serial.printf_P(PSTR("logs enabled: "));
if (0 == g.log_bitmask) {
@ -78,15 +80,16 @@ print_log_menu(void)
}
Serial.println();
if (last_log_num == 0) {
if (num_logs == 0) {
Serial.printf_P(PSTR("\nNo logs available for download\n"));
}else{
Serial.printf_P(PSTR("\n%d logs available for download\n"), last_log_num);
for(int i=1;i<last_log_num+1;i++) {
get_log_boundaries(i, log_start, log_end);
Serial.printf_P(PSTR("\n%d logs available for download\n"), num_logs);
for(int i=num_logs;i>=1;i--) {
temp = g.log_last_filenumber-i+1;
get_log_boundaries(temp, log_start, log_end);
Serial.printf_P(PSTR("Log number %d, start page %d, end page %d\n"),
i, log_start, log_end);
temp, log_start, log_end);
}
Serial.println();
}
@ -103,8 +106,8 @@ dump_log(uint8_t argc, const Menu::arg *argv)
// check that the requested log number can be read
dump_log = argv[1].i;
last_log_num = get_num_logs();
if ((argc != 2) || (dump_log < 1) || (dump_log > last_log_num)) {
last_log_num = g.log_last_filenumber;
if ((argc != 2) || (dump_log <= (last_log_num - get_num_logs())) || (dump_log > last_log_num)) {
Serial.printf_P(PSTR("bad log number\n"));
return(-1);
}
@ -128,15 +131,13 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
delay(1000);
}
Serial.printf_P(PSTR("\nErasing log...\n"));
for(int j = 1; j < 4096; j++)
DataFlash.SetFileNumber(0xFFFF);
for(int j = 1; j <= DF_LAST_PAGE; j++) {
DataFlash.PageErase(j);
DataFlash.StartWrite(1);
DataFlash.WriteByte(HEAD_BYTE1);
DataFlash.WriteByte(HEAD_BYTE2);
DataFlash.WriteByte(LOG_INDEX_MSG);
DataFlash.WriteByte(0);
DataFlash.WriteByte(END_BYTE);
DataFlash.FinishWrite();
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
}
g.log_last_filenumber.set_and_save(0);
Serial.printf_P(PSTR("\nLog erased.\n"));
return 0;
}
@ -194,137 +195,196 @@ process_logs(uint8_t argc, const Menu::arg *argv)
static byte get_num_logs(void)
{
int page = 1;
byte data;
byte log_step = 0;
uint16_t lastpage;
uint16_t last;
uint16_t first;
/*
for (int counter=1;counter<=4096;counter++){
DataFlash.StartRead(counter);
Serial.print(counter, DEC); Serial.print("\t");
Serial.print(DataFlash.GetFileNumber(), DEC); Serial.print("\t");
Serial.println(DataFlash.GetFilePage(), DEC);
}
*/
if(g.log_last_filenumber < 1) return 0;
DataFlash.StartRead(1);
//Serial.print("getfilenumber: ");
//Serial.println(DataFlash.GetFileNumber(), DEC);
if(DataFlash.GetFileNumber() == 0XFFFF) return 0;
while (page == 1) {
data = DataFlash.ReadByte();
switch(log_step){ //This is a state machine to read the packets
case 0:
if(data==HEAD_BYTE1) // Head byte 1
log_step++;
break;
case 1:
if(data==HEAD_BYTE2) // Head byte 2
log_step++;
else
log_step = 0;
break;
case 2:
if(data==LOG_INDEX_MSG){
byte num_logs = DataFlash.ReadByte();
return num_logs;
}else{
log_step=0; // Restart, we have a problem...
lastpage = find_last_log_page(g.log_last_filenumber);
//Serial.println(lastpage, DEC);
DataFlash.StartRead(lastpage);
last = DataFlash.GetFileNumber();
//Serial.println(last, DEC);
DataFlash.StartRead(lastpage + 2);
first = DataFlash.GetFileNumber();
//Serial.println(first, DEC);
if(first == 0xFFFF) {
DataFlash.StartRead(1);
first = DataFlash.GetFileNumber();
}
break;
}
page = DataFlash.GetPage();
}
return 0;
}
// send the number of the last log?
static void start_new_log(byte num_existing_logs)
if(last == first)
{
int start_pages[50] = {0,0,0};
int end_pages[50] = {0,0,0};
if(num_existing_logs > 0) {
for(int i=0;i<num_existing_logs;i++) {
get_log_boundaries(i+1,start_pages[i],end_pages[i]);
}
end_pages[num_existing_logs - 1] = find_last_log_page(start_pages[num_existing_logs - 1]);
}
if(num_existing_logs == 0 ||
(end_pages[num_existing_logs - 1] < 4095 && num_existing_logs < MAX_NUM_LOGS)) {
if(num_existing_logs > 0)
start_pages[num_existing_logs] = end_pages[num_existing_logs - 1] + 1;
else
start_pages[0] = 2;
num_existing_logs++;
DataFlash.StartWrite(1);
DataFlash.WriteByte(HEAD_BYTE1);
DataFlash.WriteByte(HEAD_BYTE2);
DataFlash.WriteByte(LOG_INDEX_MSG);
DataFlash.WriteByte(num_existing_logs);
for(int i=0;i<MAX_NUM_LOGS;i++) {
DataFlash.WriteInt(start_pages[i]);
DataFlash.WriteInt(end_pages[i]);
}
DataFlash.WriteByte(END_BYTE);
DataFlash.FinishWrite();
DataFlash.StartWrite(start_pages[num_existing_logs-1]);
return 1;
} else {
gcs_send_text_P(SEVERITY_LOW,PSTR("<start_new_log> Logs full - logging discontinued"));
return (last - first + 1);
}
}
static void start_new_log()
{
uint16_t last_page;
//Serial.print("last filenumber: "); Serial.println(g.log_last_filenumber, DEC);
if(g.log_last_filenumber < 1) {
last_page = 0;
} else {
last_page = find_last_log_page(g.log_last_filenumber);
}
g.log_last_filenumber.set_and_save(g.log_last_filenumber+1);
//Serial.print("last filenumber: "); Serial.println(g.log_last_filenumber, DEC);
DataFlash.SetFileNumber(g.log_last_filenumber);
DataFlash.StartWrite(last_page + 1);
}
static void get_log_boundaries(byte log_num, int & start_page, int & end_page)
{
int page = 1;
byte data;
byte log_step = 0;
DataFlash.StartRead(1);
while (page == 1) {
data = DataFlash.ReadByte();
switch(log_step) //This is a state machine to read the packets
int num = get_num_logs();
if(num == 1)
{
case 0:
if(data==HEAD_BYTE1) // Head byte 1
log_step++;
break;
case 1:
if(data==HEAD_BYTE2) // Head byte 2
log_step++;
else
log_step = 0;
break;
case 2:
if(data==LOG_INDEX_MSG){
byte num_logs = DataFlash.ReadByte();
for(int i=0;i<log_num;i++) {
start_page = DataFlash.ReadInt();
end_page = DataFlash.ReadInt();
}
if(log_num==num_logs)
end_page = find_last_log_page(start_page);
return; // This is the normal exit point
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
{
start_page = 1;
end_page = find_last_log_page((uint16_t)log_num);
} else {
log_step=0; // Restart, we have a problem...
}
break;
}
page = DataFlash.GetPage();
}
// Error condition if we reach here with page = 2 TO DO - report condition
end_page = find_last_log_page((uint16_t)log_num);
start_page = end_page + 1;
}
static int find_last_log_page(int bottom_page)
} else {
end_page = find_last_log_page((uint16_t)log_num);
if(log_num==1)
start_page = 1;
else
if(log_num == g.log_last_filenumber - num + 1) {
start_page = find_last_log_page(g.log_last_filenumber) + 1;
} else {
start_page = find_last_log_page((uint16_t)(log_num-1)) + 1;
}
}
if(start_page == DF_LAST_PAGE+1 || start_page == 0) start_page=1;
}
static int find_last_log_page(uint16_t log_number)
{
int top_page = 4096;
int look_page;
int32_t check;
int16_t bottom_page;
int16_t top_page;
int16_t bottom_page_file;
int16_t bottom_page_filepage;
int16_t top_page_file;
int16_t top_page_filepage;
int16_t look_page;
int16_t look_page_file;
int16_t look_page_filepage;
int16_t check;
//Serial.print("in find last log page looking for: "); Serial.println(log_number, DEC);
// First see if the logs are empty
DataFlash.StartRead(1);
if(DataFlash.GetFileNumber() == 0XFFFF) {
//Serial.println("not here");
return 0;
}
// Next, see if logs wrap the top of the dataflash
DataFlash.StartRead(DF_LAST_PAGE);
if(DataFlash.GetFileNumber() == 0xFFFF)
{
// This case is that we have not wrapped the top of the dataflash
top_page = DF_LAST_PAGE;
bottom_page = 1;
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
check = DataFlash.ReadLong();
if(check == -1L)
//Serial.print("look page: ");
//Serial.print(look_page, DEC);
//Serial.print("\t ");
//Serial.println(DataFlash.GetFileNumber(), DEC);
if(DataFlash.GetFileNumber() > log_number)
top_page = look_page;
else
bottom_page = look_page;
}
return top_page;
return bottom_page;
} else {
// The else case is that the logs do wrap the top of the dataflash
bottom_page = 1;
top_page = DF_LAST_PAGE;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
DataFlash.StartRead(top_page);
top_page_file = DataFlash.GetFileNumber();
top_page_filepage = DataFlash.GetFilePage();
// Check is we have exactly filled the dataflash but not wrapped
if(top_page_file == log_number && bottom_page_file != log_number)
{
return top_page_file;
}
// Check if the top is 1 file higher than we want. If so we can exit quickly.
if(top_page_file == log_number+1)
{
//Serial.println("There");
return top_page - top_page_filepage;
}
// Step down through the files to find the one we want
bottom_page = top_page;
bottom_page_filepage = top_page_filepage;
do
{
top_page = bottom_page;
bottom_page = bottom_page - bottom_page_filepage;
if(bottom_page < 1) bottom_page = 1;
DataFlash.StartRead(bottom_page);
bottom_page_file = DataFlash.GetFileNumber();
bottom_page_filepage = DataFlash.GetFilePage();
//Serial.print("Page, File and Pages: "); //Serial.print(bottom_page, DEC); Serial.print("\t");Serial.print(bottom_page_file, DEC); Serial.print("\t"); Serial.println(bottom_page_filepage);
} while (bottom_page_file != log_number);
Serial.print("bottom Page, File and Pages: "); Serial.print(bottom_page, DEC); Serial.print("\t");Serial.print(bottom_page_file, DEC); Serial.print("\t"); Serial.println(bottom_page_filepage);
// Check if we have wrapped multiple times
if(bottom_page == 1 && bottom_page_file == log_number) return DF_LAST_PAGE;
// Deal with stepping down too far due to overwriting a file
while((top_page - bottom_page) > 1) {
look_page = (top_page + bottom_page) / 2;
DataFlash.StartRead(look_page);
//Serial.print("look page2: ");
//Serial.print(look_page, DEC);
//Serial.print("\t ");
//Serial.println(DataFlash.GetFileNumber(), DEC);
if(DataFlash.GetFileNumber() < log_number)
top_page = look_page;
else
bottom_page = look_page;
}
return bottom_page;
}
}
@ -341,6 +401,7 @@ static void Log_Write_Attitude(int log_roll, int log_pitch, uint16_t log_yaw)
}
// Write a performance monitoring packet. Total length : 19 bytes
#if HIL_MODE != HIL_MODE_ATTITUDE
static void Log_Write_Performance()
{
DataFlash.WriteByte(HEAD_BYTE1);
@ -361,6 +422,7 @@ static void Log_Write_Performance()
DataFlash.WriteInt(pmTest1);
DataFlash.WriteByte(END_BYTE);
}
#endif
// Write a command processing packet. Total length : 19 bytes
//void Log_Write_Cmd(byte num, byte id, byte p1, long alt, long lat, long lng)
@ -645,10 +707,7 @@ static void Log_Read_Raw()
// Read the DataFlash log memory : Packet Parser
static void Log_Read(int start_page, int end_page)
{
byte data;
byte log_step = 0;
int packet_count = 0;
int page = start_page;
#ifdef AIRFRAME_NAME
Serial.printf_P(PSTR((AIRFRAME_NAME)
@ -657,6 +716,25 @@ static void Log_Read(int start_page, int end_page)
"\nFree RAM: %u\n"),
memcheck_available_memory());
if(start_page > end_page)
{
packet_count = Log_Read_Process(start_page, DF_LAST_PAGE);
packet_count += Log_Read_Process(1, end_page);
} else {
packet_count = Log_Read_Process(start_page, end_page);
}
Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count);
}
// Read the DataFlash log memory : Packet Parser
static int Log_Read_Process(int start_page, int end_page)
{
byte data;
byte log_step = 0;
int page = start_page;
int packet_count = 0;
DataFlash.StartRead(start_page);
while (page < end_page && page != -1){
data = DataFlash.ReadByte();
@ -729,7 +807,6 @@ static void Log_Read(int start_page, int end_page)
}
page = DataFlash.GetPage();
}
Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count);
}
#else // LOGGING_ENABLED
@ -745,7 +822,7 @@ static void Log_Write_GPS( long log_Time, long log_Lattitude, long log_Longitude
static void Log_Write_Performance() {}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
static byte get_num_logs(void) { return 0; }
static void start_new_log(byte num_existing_logs) {}
static void start_new_log() {}
static void Log_Write_Attitude(int log_roll, int log_pitch, uint16_t log_yaw) {}
static void Log_Write_Control_Tuning() {}
static void Log_Write_Raw() {}

View File

@ -69,6 +69,7 @@ public:
k_param_flap_2_percent,
k_param_flap_2_speed,
k_param_num_resets,
k_param_log_last_filenumber,
// 110: Telemetry control
@ -305,6 +306,7 @@ public:
AP_Int8 reverse_ch2_elevon;
AP_Int16 num_resets;
AP_Int16 log_bitmask;
AP_Int16 log_last_filenumber;
AP_Int16 airspeed_cruise;
AP_Int16 pitch_trim;
AP_Int16 RTL_altitude;
@ -410,6 +412,7 @@ public:
reverse_ch2_elevon (ELEVON_CH2_REVERSE, k_param_reverse_ch2_elevon, PSTR("ELEVON_CH2_REV")),
num_resets (0, k_param_num_resets, PSTR("SYS_NUM_RESETS")),
log_bitmask (DEFAULT_LOG_BITMASK, k_param_log_bitmask, PSTR("LOG_BITMASK")),
log_last_filenumber (0, k_param_log_last_filenumber, PSTR("LOG_LASTFILE")),
airspeed_cruise (AIRSPEED_CRUISE_CM, k_param_airspeed_cruise, PSTR("TRIM_ARSPD_CM")),
pitch_trim (0, k_param_pitch_trim, PSTR("TRIM_PITCH_CD")),
RTL_altitude (ALT_HOLD_HOME_CM, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),

View File

@ -210,10 +210,7 @@ static void init_ardupilot()
#endif // CLI_ENABLED
if(g.log_bitmask != 0){
// TODO - Here we will check on the length of the last log
// We don't want to create a bunch of little logs due to powering on and off
byte last_log_num = get_num_logs();
start_new_log(last_log_num);
start_new_log();
}
// read in the flight switches

View File

@ -35,7 +35,7 @@
#include "DataFlash.h"
#include <SPI.h>
#define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1
#define OVERWRITE_DATA 1 // 0: When reach the end page stop, 1: Start overwriting from page 1
// *** INTERNAL FUNCTIONS ***
@ -160,6 +160,7 @@ void DataFlash_Class::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
dataflash_CS_inactive();
}
void DataFlash_Class::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
@ -271,10 +272,15 @@ void DataFlash_Class::ChipErase ()
void DataFlash_Class::StartWrite(int PageAdr)
{
df_BufferNum=1;
df_BufferIdx=0;
df_BufferIdx=4;
df_PageAdr=PageAdr;
df_Stop_Write=0;
WaitReady();
// We are starting a new page - write FileNumber and FilePage
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
}
void DataFlash_Class::FinishWrite(void)
@ -284,12 +290,12 @@ void DataFlash_Class::FinishWrite(void)
df_PageAdr++;
if (OVERWRITE_DATA==1)
{
if (df_PageAdr>=4096) // If we reach the end of the memory, start from the begining
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
df_PageAdr = 1;
}
else
{
if (df_PageAdr>=4096) // If we reach the end of the memory, stop here
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
df_Stop_Write=1;
}
@ -308,17 +314,17 @@ void DataFlash_Class::WriteByte(byte data)
df_BufferIdx++;
if (df_BufferIdx >= df_PageSize) // End of buffer?
{
df_BufferIdx=0;
df_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
df_PageAdr++;
if (OVERWRITE_DATA==1)
{
if (df_PageAdr>=4096) // If we reach the end of the memory, start from the begining
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
df_PageAdr = 1;
}
else
{
if (df_PageAdr>=4096) // If we reach the end of the memory, stop here
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
df_Stop_Write=1;
}
@ -326,6 +332,12 @@ void DataFlash_Class::WriteByte(byte data)
df_BufferNum=2;
else
df_BufferNum=1;
// We are starting a new page - write FileNumber and FilePage
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
df_FilePage++;
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
}
}
}
@ -359,11 +371,19 @@ int DataFlash_Class::GetPage()
void DataFlash_Class::StartRead(int PageAdr)
{
df_Read_BufferNum=1;
df_Read_BufferIdx=0;
df_Read_BufferIdx=4;
df_Read_PageAdr=PageAdr;
WaitReady();
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer
//Serial.print(df_Read_PageAdr, DEC); Serial.print("\t");
df_Read_PageAdr++;
// We are starting a new page - read FileNumber and FilePage
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
//Serial.print(df_FileNumber, DEC); Serial.print("\t");
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
//Serial.println(df_FileNumber, DEC); Serial.print("\t");
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
}
byte DataFlash_Class::ReadByte()
@ -375,14 +395,19 @@ byte DataFlash_Class::ReadByte()
df_Read_BufferIdx++;
if (df_Read_BufferIdx >= df_PageSize) // End of buffer?
{
df_Read_BufferIdx=0;
df_Read_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer
df_Read_PageAdr++;
if (df_Read_PageAdr>=4096) // If we reach the end of the memory, start from the begining
if (df_Read_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
{
df_Read_PageAdr = 0;
df_Read_END = true;
}
// We are starting a new page - read FileNumber and FilePage
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
}
return result;
}
@ -407,5 +432,23 @@ long DataFlash_Class::ReadLong()
return result;
}
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Class::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Class::GetFilePage()
{
return df_FilePage;
}
// make one instance for the user to use
DataFlash_Class DataFlash;

View File

@ -4,6 +4,10 @@
#ifndef DataFlash_h
#define DataFlash_h
#include "../FastSerial/FastSerial.h"
// flash size
#define DF_LAST_PAGE 4096
// arduino mega SPI pins
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define DF_DATAOUT 51 // MOSI
@ -45,15 +49,24 @@ class DataFlash_Class
unsigned char df_BufferNum;
unsigned char df_Read_BufferNum;
uint16_t df_BufferIdx;
uint16_t df_Read_BufferIdx;
uint16_t df_PageAdr;
uint16_t df_Read_PageAdr;
unsigned char df_Read_END;
unsigned char df_Stop_Write;
uint16_t df_FileNumber;
uint16_t df_FilePage;
//Methods
unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr);
void BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data);
void BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait);
void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr);
void WaitReady();
unsigned char ReadStatusReg();
@ -71,20 +84,30 @@ class DataFlash_Class
void ReadManufacturerID();
int16_t GetPage();
int16_t GetWritePage();
void PageErase (uint16_t PageAdr);
void ChipErase ();
// Write methods
void StartWrite(int16_t PageAdr);
void FinishWrite();
void WriteByte(unsigned char data);
void WriteInt(int16_t data);
void WriteLong(int32_t data);
// Read methods
void StartRead(int16_t PageAdr);
unsigned char ReadByte();
int16_t ReadInt();
int32_t ReadLong();
void SetFileNumber(uint16_t FileNumber);
uint16_t GetFileNumber();
uint16_t GetFilePage();
};
extern DataFlash_Class DataFlash;