mirror of https://github.com/ArduPilot/ardupilot
DataFlash: report log number when starting a new log
helps with test sketch
This commit is contained in:
parent
cf62619108
commit
a7541e9ad3
|
@ -38,7 +38,7 @@ public:
|
|||
virtual uint16_t find_last_log(void) = 0;
|
||||
virtual void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
||||
virtual uint8_t get_num_logs(void) = 0;
|
||||
virtual void start_new_log(void) = 0;
|
||||
virtual uint16_t start_new_log(void) = 0;
|
||||
virtual uint16_t log_read_process(uint8_t log_num,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
void (*callback)(uint8_t msgid)) = 0;
|
||||
|
|
|
@ -39,7 +39,7 @@ public:
|
|||
uint16_t find_last_log(void);
|
||||
void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||
uint8_t get_num_logs(void);
|
||||
void start_new_log(void);
|
||||
uint16_t start_new_log(void);
|
||||
uint16_t log_read_process(uint8_t log_num,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
void (*callback)(uint8_t msgid));
|
||||
|
|
|
@ -36,7 +36,7 @@ public:
|
|||
uint16_t find_last_log(void);
|
||||
void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||
uint8_t get_num_logs(void);
|
||||
void start_new_log(void);
|
||||
uint16_t start_new_log(void);
|
||||
uint16_t log_read_process(uint8_t log_num,
|
||||
uint16_t start_page, uint16_t end_page,
|
||||
void (*callback)(uint8_t msgid));
|
||||
|
|
|
@ -40,7 +40,7 @@ uint8_t DataFlash_Block::get_num_logs(void)
|
|||
|
||||
|
||||
// This function starts a new log file in the DataFlash
|
||||
void DataFlash_Block::start_new_log(void)
|
||||
uint16_t DataFlash_Block::start_new_log(void)
|
||||
{
|
||||
uint16_t last_page = find_last_page();
|
||||
|
||||
|
@ -53,20 +53,27 @@ void DataFlash_Block::start_new_log(void)
|
|||
SetFileNumber(1);
|
||||
StartWrite(1);
|
||||
//Serial.println("start log from 0");
|
||||
return;
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint16_t new_log_num;
|
||||
|
||||
// Check for log of length 1 page and suppress
|
||||
if(GetFilePage() <= 1) {
|
||||
SetFileNumber(GetFileNumber()); // Last log too short, reuse its number
|
||||
StartWrite(last_page); // and overwrite it
|
||||
//Serial.println("start log from short");
|
||||
new_log_num = GetFileNumber();
|
||||
// Last log too short, reuse its number
|
||||
// and overwrite it
|
||||
SetFileNumber(new_log_num);
|
||||
StartWrite(last_page);
|
||||
} else {
|
||||
if(last_page == 0xFFFF) last_page=0;
|
||||
SetFileNumber(GetFileNumber()+1);
|
||||
new_log_num = GetFileNumber()+1;
|
||||
if (last_page == 0xFFFF) {
|
||||
last_page=0;
|
||||
}
|
||||
SetFileNumber(new_log_num);
|
||||
StartWrite(last_page + 1);
|
||||
//Serial.println("start log normal");
|
||||
}
|
||||
return new_log_num;
|
||||
}
|
||||
|
||||
// This function finds the first and last pages of a log file
|
||||
|
@ -76,6 +83,10 @@ void DataFlash_Block::get_log_boundaries(uint8_t log_num, uint16_t & start_page,
|
|||
uint16_t num = get_num_logs();
|
||||
uint16_t look;
|
||||
|
||||
if (df_BufferIdx != 0) {
|
||||
FinishWrite();
|
||||
}
|
||||
|
||||
if(num == 1)
|
||||
{
|
||||
StartRead(df_NumPages);
|
||||
|
@ -245,6 +256,10 @@ uint16_t DataFlash_Block::log_read_process(uint8_t log_num,
|
|||
uint16_t page = start_page;
|
||||
uint16_t packet_count = 0;
|
||||
|
||||
if (df_BufferIdx != 0) {
|
||||
FinishWrite();
|
||||
}
|
||||
|
||||
StartRead(start_page);
|
||||
|
||||
while (true) {
|
||||
|
|
Loading…
Reference in New Issue