@ -6,22 +6,25 @@
@@ -6,22 +6,25 @@
# include <AP_HAL/AP_HAL.h>
# include <stdio.h>
# include <AP_RTC/AP_RTC.h>
# include <GCS_MAVLink/GCS.h>
const 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 0x1901201A
# define DF_LOGGING_FORMAT 0x1901201B
AP_Logger_Block : : AP_Logger_Block ( AP_Logger & front , LoggerMessageWriter_DFLogStart * writer ) :
writebuf ( 0 ) ,
AP_Logger_Backend ( front , writer )
{
// buffer is used for both reads and writes so access must always be within the semaphore
buffer = ( uint8_t * ) hal . util - > malloc_type ( page_size_max , AP_HAL : : Util : : MEM_DMA_SAFE ) ;
if ( buffer = = nullptr ) {
AP_HAL : : panic ( " Out of DMA memory for logging " ) ;
}
df_stats_clear ( ) ;
}
// init is called after backend init
@ -56,8 +59,6 @@ void AP_Logger_Block::Init(void)
@@ -56,8 +59,6 @@ void AP_Logger_Block::Init(void)
WITH_SEMAPHORE ( sem ) ;
hal . scheduler - > register_io_process ( FUNCTOR_BIND_MEMBER ( & AP_Logger_Block : : io_timer , void ) ) ;
AP_Logger_Backend : : Init ( ) ;
}
uint32_t AP_Logger_Block : : bufferspace_available ( )
@ -71,7 +72,6 @@ uint32_t AP_Logger_Block::bufferspace_available()
@@ -71,7 +72,6 @@ uint32_t AP_Logger_Block::bufferspace_available()
void AP_Logger_Block : : StartWrite ( uint32_t PageAdr )
{
df_PageAdr = PageAdr ;
log_write_started = true ;
}
void AP_Logger_Block : : FinishWrite ( void )
@ -87,13 +87,25 @@ void AP_Logger_Block::FinishWrite(void)
@@ -87,13 +87,25 @@ void AP_Logger_Block::FinishWrite(void)
// when starting a new sector, erase it
if ( ( df_PageAdr - 1 ) % df_PagePerBlock = = 0 ) {
// if we have wrapped over an existing log, force the oldest to be recalculated
if ( _cached_oldest_log > 0 ) {
uint16_t log_num = StartRead ( df_PageAdr ) ;
if ( log_num ! = 0xFFFF & & log_num > = _cached_oldest_log ) {
_cached_oldest_log = 0 ;
}
}
// are we about to erase a sector with our own headers in it?
if ( df_Write_FilePage > df_NumPages - df_PagePerBlock ) {
chip_full = true ;
return ;
}
SectorErase ( df_PageAdr / df_PagePerBlock ) ;
}
}
bool AP_Logger_Block : : WritesOK ( ) const
{
if ( ! CardInserted ( ) ) {
if ( ! CardInserted ( ) | | erase_started ) {
return false ;
}
return true ;
@ -108,21 +120,57 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
@@ -108,21 +120,57 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
return false ;
}
if ( ! WriteBlockCheckStartupMessages ( ) ) {
if ( ! WriteBlockCheckStartupMessages ( ) ) {
_dropped + + ;
return false ;
}
if ( writebuf . space ( ) < size ) {
// no room in buffer
if ( ! write_sem . take ( 1 ) ) {
return false ;
}
uint32_t space = writebuf . space ( ) ;
if ( _writing_startup_messages & &
_startup_messagewriter - > fmt_done ( ) ) {
// the state machine has called us, and it has finished
// writing format messages out. It can always get back to us
// with more messages later, so let's leave room for other
// things:
const uint32_t now = AP_HAL : : millis ( ) ;
const bool must_dribble = ( now - last_messagewrite_message_sent ) > 100 ;
if ( ! must_dribble & &
space < non_messagewriter_message_reserved_space ( writebuf . get_size ( ) ) ) {
// this message isn't dropped, it will be sent again...
write_sem . give ( ) ;
return false ;
}
last_messagewrite_message_sent = now ;
} else {
// we reserve some amount of space for critical messages:
if ( ! is_critical & & space < critical_message_reserved_space ( writebuf . get_size ( ) ) ) {
_dropped + + ;
write_sem . give ( ) ;
return false ;
}
}
// if no room for entire message - drop it:
if ( space < size ) {
_dropped + + ;
write_sem . give ( ) ;
return false ;
}
writebuf . write ( ( uint8_t * ) pBuffer , size ) ;
df_stats_gather ( size , writebuf . space ( ) ) ;
write_sem . give ( ) ;
return true ;
}
void AP_Logger_Block : : StartRead ( uint32_t PageAdr )
// read from the page address and return the file number at that location
uint16_t AP_Logger_Block : : StartRead ( uint32_t PageAdr )
{
df_Read_PageAdr = PageAdr ;
@ -132,13 +180,32 @@ void AP_Logger_Block::StartRead(uint32_t PageAdr)
@@ -132,13 +180,32 @@ void AP_Logger_Block::StartRead(uint32_t PageAdr)
} else {
PageToBuffer ( df_Read_PageAdr ) ;
}
return ReadHeaders ( ) ;
}
// read the headers at the current read point returning the file number
uint16_t AP_Logger_Block : : ReadHeaders ( )
{
// We are starting a new page - read FileNumber and FilePage
struct PageHeader ph ;
BlockRead ( 0 , & ph , sizeof ( ph ) ) ;
df_FileNumber = ph . FileNumber ;
df_FilePage = ph . FilePage ;
# if BLOCK_LOG_VALIDATE
if ( ph . crc ! = DF_LOGGING_FORMAT + df_FilePage & & df_FileNumber ! = 0xFFFF ) {
printf ( " ReadHeaders: invalid block read at %d \n " , df_Read_PageAdr ) ;
}
# endif
df_Read_BufferIdx = sizeof ( ph ) ;
// we are at the start of a file, read the file header
if ( df_FilePage = = 1 ) {
struct FileHeader fh ;
BlockRead ( 0 , & fh , sizeof ( fh ) ) ;
df_FileTime = fh . utc_secs ;
df_Read_BufferIdx + = sizeof ( fh ) ;
}
return df_FileNumber ;
}
bool AP_Logger_Block : : ReadBlock ( void * pBuffer , uint16_t size )
@ -172,23 +239,19 @@ bool AP_Logger_Block::ReadBlock(void *pBuffer, uint16_t size)
@@ -172,23 +239,19 @@ bool AP_Logger_Block::ReadBlock(void *pBuffer, uint16_t size)
}
// We are starting a new page - read FileNumber and FilePage
struct PageHeader ph ;
if ( ! BlockRead ( 0 , & ph , sizeof ( ph ) ) ) {
return false ;
}
df_FileNumber = ph . FileNumber ;
df_FilePage = ph . FilePage ;
df_Read_BufferIdx = sizeof ( ph ) ;
ReadHeaders ( ) ;
}
}
return true ;
}
void AP_Logger_Block : : SetFileNumber ( uint16_t FileNumber )
// initialize the log data for the given file number
void AP_Logger_Block : : StartLogFile ( uint16_t FileNumber )
{
df_FileNumber = FileNumber ;
df_Write_FileNumber = FileNumber ;
df_FilePage = 1 ;
df_Write_FilePage = 1 ;
}
uint16_t AP_Logger_Block : : GetFileNumber ( )
@ -198,38 +261,104 @@ uint16_t AP_Logger_Block::GetFileNumber()
@@ -198,38 +261,104 @@ uint16_t AP_Logger_Block::GetFileNumber()
void AP_Logger_Block : : EraseAll ( )
{
if ( hal . util - > get_soft_armed ( ) ) {
// do not want to do any filesystem operations while we are e.g. flying
return ;
}
// push out the message before stopping logging
if ( ! erase_started ) {
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " Chip erase started " ) ;
}
WITH_SEMAPHORE ( sem ) ;
if ( erase_started ) {
// already erasing
return ;
}
erase_started = true ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Chip erase started " ) ;
// reset the format version and wrapped status so that any incomplete erase will be caught
Sector4kErase ( get_sector ( df_NumPages ) ) ;
// remember what we were doing
new_log_pending = log_write_started ;
// throw away everything
log_write_started = false ;
writebuf . clear ( ) ;
// reset the format version and wrapped status so that any incomplete erase will be caught
Sector4kErase ( get_sector ( df_NumPages ) ) ;
StartErase ( ) ;
erase_started = true ;
}
bool AP_Logger_Block : : NeedPrep ( void )
void AP_Logger_Block : : periodic_1Hz ( )
{
AP_Logger_Backend : : periodic_1Hz ( ) ;
if ( ! io_thread_alive ( ) ) {
if ( warning_decimation_counter = = 0 & & _initialised ) {
// we don't print this error unless we did initialise. When _initialised is set to true
// we register the IO timer callback
GCS_SEND_TEXT ( MAV_SEVERITY_CRITICAL , " AP_Logger: IO thread died " ) ;
}
if ( warning_decimation_counter + + > 57 ) {
warning_decimation_counter = 0 ;
}
_initialised = false ;
} else if ( chip_full ) {
if ( warning_decimation_counter = = 0 ) {
GCS_SEND_TEXT ( MAV_SEVERITY_WARNING , " Chip full, logging stopped " ) ;
}
if ( warning_decimation_counter + + > 57 ) {
warning_decimation_counter = 0 ;
}
}
}
// EraseAll is asynchronous, but we must not start a new
// log in a child thread so this task picks up the hint from the io timer
// keeping locking to a minimum
void AP_Logger_Block : : periodic_10Hz ( const uint32_t now )
{
return NeedErase ( ) ;
if ( erase_started | | InErase ( ) ) {
return ;
}
// don't print status messages in io thread, do it here
switch ( status_msg ) {
case StatusMessage : : ERASE_COMPLETE :
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " Chip erase complete " ) ;
status_msg = StatusMessage : : NONE ;
break ;
case StatusMessage : : RECOVERY_COMPLETE :
GCS_SEND_TEXT ( MAV_SEVERITY_WARNING , " Log recovery complete " ) ;
status_msg = StatusMessage : : NONE ;
break ;
case StatusMessage : : NONE :
break ;
}
// EraseAll should only set this in the main thread
if ( new_log_pending ) {
start_new_log ( ) ;
}
}
void AP_Logger_Block : : Prep ( )
{
WITH_SEMAPHORE ( sem ) ;
if ( hal . util - > get_soft_armed ( ) ) {
// do not want to do any filesystem operations while we are e.g. flying
return ;
}
WITH_SEMAPHORE ( sem ) ;
if ( NeedErase ( ) ) {
EraseAll ( ) ;
} else {
validate_log_structure ( ) ;
}
validate_log_structure ( ) ;
}
/*
@ -238,11 +367,11 @@ void AP_Logger_Block::Prep()
@@ -238,11 +367,11 @@ void AP_Logger_Block::Prep()
bool AP_Logger_Block : : NeedErase ( void )
{
uint32_t version = 0 ;
StartRead ( df_NumPages + 1 ) ; // last page
PageToBuffer ( df_NumPages + 1 ) ; // last page
BlockRead ( 0 , & version , sizeof ( version ) ) ;
StartRead ( 1 ) ;
if ( version = = DF_LOGGING_FORMAT ) {
// only leave the read point in a sane place if we are not about to destroy everything
StartRead ( 1 ) ;
return false ;
}
return true ;
@ -254,12 +383,11 @@ bool AP_Logger_Block::NeedErase(void)
@@ -254,12 +383,11 @@ bool AP_Logger_Block::NeedErase(void)
void AP_Logger_Block : : validate_log_structure ( )
{
WITH_SEMAPHORE ( sem ) ;
bool wrapped = check _wrapped( ) ;
bool wrapped = is _wrapped( ) ;
uint32_t page = 1 ;
uint32_t page_start = 1 ;
StartRead ( page ) ;
uint16_t file = GetFileNumber ( ) ;
uint16_t file = StartRead ( page ) ;
uint16_t first_file = file ;
uint16_t next_file = file ;
uint16_t last_file = 0 ;
@ -270,13 +398,11 @@ void AP_Logger_Block::validate_log_structure()
@@ -270,13 +398,11 @@ void AP_Logger_Block::validate_log_structure()
break ;
}
page = end_page + 1 ;
StartRead ( page ) ;
file = GetFileNumber ( ) ;
file = StartRead ( page ) ;
next_file + + ;
// skip over the rest of an erased blc ok
// skip over the rest of an erased bloc k
if ( wrapped & & file = = 0xFFFF ) {
StartRead ( ( get_block ( page ) + 1 ) * df_PagePerBlock + 1 ) ;
file = GetFileNumber ( ) ;
file = StartRead ( ( get_block ( page ) + 1 ) * df_PagePerBlock + 1 ) ;
}
if ( wrapped & & file < next_file ) {
page_start = page ;
@ -291,34 +417,40 @@ void AP_Logger_Block::validate_log_structure()
@@ -291,34 +417,40 @@ void AP_Logger_Block::validate_log_structure()
}
if ( file ! = 0xFFFF & & file ! = next_file & & page < = df_NumPages & & page > 0 ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Found corrupt log %d at 0x%04X, erasing " , int ( file ) , unsigned ( page ) ) ;
hal . console - > printf ( " Found corrupt log %d at 0x%04X, erasing " , int ( file ) , unsigned ( page ) ) ;
df_EraseFrom = page ;
} else if ( next_file ! = 0xFFFF & & page > 0 & & next_file > 1 ) { // chip is empty
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Found %d complete logs at 0x%04X-0x%04X " , int ( next_file - first_file ) , unsigned ( page_start ) , unsigned ( page - 1 ) ) ;
hal . console - > printf ( " Found %d complete logs at 0x%04X-0x%04X " , int ( next_file - first_file ) , unsigned ( page_start ) , unsigned ( page - 1 ) ) ;
}
}
/**
get raw data from a log
* get raw data from a log - page is the start page of the log , offset is the offset within the log starting at that page
*/
int16_t AP_Logger_Block : : get_log_data_raw ( uint16_t log_num , uint32_t page , uint32_t offset , uint16_t len , uint8_t * data )
{
WITH_SEMAPHORE ( sem ) ;
uint16_t data_page_size = df_PageSize - sizeof ( struct PageHeader ) ;
const uint16_t data_page_size = df_PageSize - sizeof ( struct PageHeader ) ;
const uint16_t first_page_size = data_page_size - sizeof ( struct FileHeader ) ;
// offset is the true offset in the file, so we have to calculate the offset accounting for page headers
if ( offset > = first_page_size ) {
offset - = first_page_size ;
page = page + offset / data_page_size + 1 ;
offset % = data_page_size ;
if ( offset > = data_page_size ) {
page + = offset / data_page_size ;
offset = offset % data_page_size ;
if ( page > df_NumPages ) {
// pages are one based, not zero
page = 1 + page - df_NumPages ;
page = page % df_NumPages ;
}
}
if ( log_write_started | | df_Read_PageAdr ! = page ) {
StartRead ( page ) ;
// Sanity check we haven't been asked for an offset beyond the end of the log
if ( StartRead ( page ) ! = log_num ) {
return - 1 ;
}
df_Read_BufferIdx = offset + sizeof ( struct PageHeader ) ;
df_Read_BufferIdx + = offset ;
if ( ! ReadBlock ( data , len ) ) {
return - 1 ;
}
@ -329,44 +461,23 @@ int16_t AP_Logger_Block::get_log_data_raw(uint16_t log_num, uint32_t page, uint3
@@ -329,44 +461,23 @@ int16_t AP_Logger_Block::get_log_data_raw(uint16_t log_num, uint32_t page, uint3
/**
get data from a log , accounting for adding FMT headers
*/
int16_t AP_Logger_Block : : get_log_data ( uint16_t log_num , uint16_t page , uint32_t offset , uint16_t len , uint8_t * data )
int16_t AP_Logger_Block : : get_log_data ( uint16_t list_entry , uint16_t page , uint32_t offset , uint16_t len , uint8_t * data )
{
WITH_SEMAPHORE ( sem ) ;
if ( offset = = 0 ) {
uint8_t header [ 3 ] ;
if ( get_log_data_raw ( log_num , page , 0 , 3 , header ) = = - 1 ) {
return - 1 ;
}
adding_fmt_headers = ( header [ 0 ] ! = HEAD_BYTE1 | | header [ 1 ] ! = HEAD_BYTE2 | | header [ 2 ] ! = LOG_FORMAT_MSG ) ;
}
uint16_t ret = 0 ;
const uint16_t log_num = log_num_from_list_entry ( list_entry ) ;
if ( adding_fmt_headers ) {
// the log doesn't start with a FMT message, we need to add
// them
const uint16_t fmt_header_size = num_types ( ) * sizeof ( struct log_Format ) ;
while ( offset < fmt_header_size & & len > 0 ) {
struct log_Format pkt ;
uint8_t t = offset / sizeof ( pkt ) ;
uint8_t ofs = offset % sizeof ( pkt ) ;
Fill_Format ( structure ( t ) , pkt ) ;
uint8_t n = sizeof ( pkt ) - ofs ;
if ( n > len ) {
n = len ;
}
memcpy ( data , ofs + ( uint8_t * ) & pkt , n ) ;
data + = n ;
offset + = n ;
len - = n ;
ret + = n ;
}
offset - = fmt_header_size ;
if ( log_num = = 0 ) {
// that failed - probably no logs
return - 1 ;
}
//printf("get_log_data(%d, %d, %d, %d)\n", log_num, page, offset, len);
WITH_SEMAPHORE ( sem ) ;
uint16_t ret = 0 ;
if ( len > 0 ) {
const int16_t bytes = get_log_data_raw ( log_num , page , offset , len , data ) ;
if ( bytes = = - 1 ) {
return ret = = 0 ? - 1 : ret ;
return - 1 ;
}
ret + = bytes ;
}
@ -375,8 +486,8 @@ int16_t AP_Logger_Block::get_log_data(uint16_t log_num, uint16_t page, uint32_t
@@ -375,8 +486,8 @@ int16_t AP_Logger_Block::get_log_data(uint16_t log_num, uint16_t page, uint32_t
}
// This function determines the number of whole or partial log files in the AP_Logger
// Wholly overwritten files are (of course) lost.
// This function determines the number of whole log files in the AP_Logger
// partial logs are rejected as without the headers they are relatively useless
uint16_t AP_Logger_Block : : get_num_logs ( void )
{
WITH_SEMAPHORE ( sem ) ;
@ -387,22 +498,24 @@ uint16_t AP_Logger_Block::get_num_logs(void)
@@ -387,22 +498,24 @@ uint16_t AP_Logger_Block::get_num_logs(void)
return 0 ;
}
StartRead ( 1 ) ;
uint32_t first = GetFileNumber ( ) ;
uint32_t first = StartRead ( 1 ) ;
if ( first = = 0xFFFF ) {
return 0 ;
}
lastpage = find_last_page ( ) ;
StartRead ( lastpage ) ;
last = GetFileNumber ( ) ;
if ( check _wrapped( ) ) {
last = StartRead ( lastpage ) ;
if ( is _wrapped( ) ) {
// if we wrapped then the rest of the block will be filled with 0xFFFF because we always erase
// a block before writing to it, in order to find the first page we therefore have to read after the
// next block boundary
StartRead ( ( get_block ( lastpage ) + 1 ) * df_PagePerBlock + 1 ) ;
first = GetFileNumber ( ) ;
first = StartRead ( ( get_block ( lastpage ) + 1 ) * df_PagePerBlock + 1 ) ;
// unless we happen to land on the first page of the file that is being overwritten we skip to the next file
if ( df_FilePage > 1 ) {
first + + ;
}
}
if ( last = = first ) {
@ -412,92 +525,135 @@ uint16_t AP_Logger_Block::get_num_logs(void)
@@ -412,92 +525,135 @@ uint16_t AP_Logger_Block::get_num_logs(void)
return ( last - first + 1 ) ;
}
// stop logging and flush any remaining data
void AP_Logger_Block : : stop_logging ( void )
{
WITH_SEMAPHORE ( sem ) ;
log_write_started = false ;
// complete writing any previous log
while ( writebuf . available ( ) ) {
write_log_page ( ) ;
}
writebuf . clear ( ) ;
}
// This function starts a new log file in the AP_Logger
// no actual data should be written to the storage here
// that should all be handled by the IO thread
void AP_Logger_Block : : start_new_log ( void )
{
if ( erase_started ) {
// already erasing
return ;
}
WITH_SEMAPHORE ( sem ) ;
if ( logging_started ( ) ) {
stop_logging ( ) ;
}
// no need to schedule this anymore
new_log_pending = false ;
uint32_t last_page = find_last_page ( ) ;
StartRead ( last_page ) ;
log_write_started = true ;
uint16_t new_log_num = 1 ;
if ( find_last_log ( ) = = 0 | | GetFileNumber ( ) = = 0xFFFF ) {
SetFileNumber ( 1 ) ;
StartLogFile ( new_log_num ) ;
StartWrite ( 1 ) ;
return ;
}
uint16_t new_log_num ;
// Check for log of length 1 page and suppress
if ( df_FilePage < = 1 ) {
} else if ( df_FilePage < = 1 ) {
new_log_num = GetFileNumber ( ) ;
// Last log too short, reuse its number
// and overwrite it
SetFileNumber ( new_log_num ) ;
StartLogFile ( new_log_num ) ;
StartWrite ( last_page ) ;
} else {
new_log_num = GetFileNumber ( ) + 1 ;
if ( last_page = = 0xFFFF ) {
last_page = 0 ;
}
SetFileNumber ( new_log_num ) ;
StartLogFile ( new_log_num ) ;
StartWrite ( last_page + 1 ) ;
}
// save UTC time in the first 4 bytes so that we can retrieve it later
uint64_t utc_usec ;
FileHeader hdr { } ;
if ( AP : : rtc ( ) . get_utc_usec ( utc_usec ) ) {
hdr . utc_secs = utc_usec / 1000000U ;
}
writebuf . write ( ( uint8_t * ) & hdr , sizeof ( FileHeader ) ) ;
start_new_log_reset_variables ( ) ;
return ;
}
// This function finds the first and last pages of a log file
// The first page may be greater than the last page if the AP_Logger has been filled and partially overwritten.
void AP_Logger_Block : : get_log_boundaries ( uint16_t log_num , uint32_t & start_page , uint32_t & end_page )
void AP_Logger_Block : : get_log_boundaries ( uint16_t list_entry , uint32_t & start_page , uint32_t & end_page )
{
const uint16_t log_num = log_num_from_list_entry ( list_entry ) ;
if ( log_num = = 0 ) {
// that failed - probably no logs
start_page = 0 ;
end_page = 0 ;
return ;
}
WITH_SEMAPHORE ( sem ) ;
uint16_t num = get_num_logs ( ) ;
uint32_t look ;
if ( num = = 1 ) {
StartRead ( df_NumPages ) ;
if ( GetFileNumber ( ) = = 0xFFFF ) {
end_page = find_last_page_of_log ( log_num ) ;
if ( num = = 1 | | log_num = = 1 ) {
if ( ! is_wrapped ( ) ) {
start_page = 1 ;
end_page = find_last_page_of_log ( ( uint16_t ) log_num ) ;
} else {
end_page = find_last_page_of_log ( ( uint16_t ) log_num ) ;
start_page = end_page + 1 ;
StartRead ( end_page ) ;
start_page = ( end_page + df_NumPages - df_FilePage ) % df_NumPages + 1 ;
}
} else {
if ( log_num = = 1 ) {
StartRead ( df_NumPages ) ;
if ( GetFileNumber ( ) = = 0xFFFF ) {
start_page = 1 ;
} else {
start_page = find_last_page ( ) + 1 ;
// looking for the first log which might have a gap in front of it
if ( list_entry = = 1 ) {
StartRead ( end_page ) ;
if ( end_page > df_FilePage ) { // log is not wrapped
start_page = end_page - df_FilePage + 1 ;
} else { // log is wrapped
start_page = ( end_page + df_NumPages - df_FilePage ) % df_NumPages + 1 ;
}
} else {
if ( log_num = = find_last_log ( ) - num + 1 ) {
start_page = find_last_page ( ) + 1 ;
} else {
look = log_num - 1 ;
do {
start_page = find_last_page_of_log ( look ) + 1 ;
look - - ;
} while ( start_page < = 0 & & look > = 1 ) ;
}
look = log_num - 1 ;
do {
start_page = find_last_page_of_log ( look ) + 1 ;
look - - ;
} while ( start_page < = 0 & & look > = 1 ) ;
}
}
if ( start_page = = df_NumPages + 1 | | start_page = = 0 ) {
if ( start_page = = df_NumPages + 1 | | start_page = = 0 ) {
start_page = 1 ;
}
end_page = find_last_page_of_log ( log_num ) ;
if ( end_page = = 0 ) {
end_page = start_page ;
}
}
bool AP_Logger_Block : : check_wrapped ( void )
// return true if logging has wrapped around to the beginning of the chip
bool AP_Logger_Block : : is_wrapped ( void )
{
StartRead ( df_NumPages ) ;
return GetFileNumber ( ) ! = 0xFFFF ;
return StartRead ( df_NumPages ) ! = 0xFFFF ;
}
@ -506,8 +662,7 @@ uint16_t AP_Logger_Block::find_last_log(void)
@@ -506,8 +662,7 @@ uint16_t AP_Logger_Block::find_last_log(void)
{
WITH_SEMAPHORE ( sem ) ;
uint32_t last_page = find_last_page ( ) ;
StartRead ( last_page ) ;
return GetFileNumber ( ) ;
return StartRead ( last_page ) ;
}
// This function finds the last page of the last file
@ -567,9 +722,8 @@ uint32_t AP_Logger_Block::find_last_page_of_log(uint16_t log_number)
@@ -567,9 +722,8 @@ uint32_t AP_Logger_Block::find_last_page_of_log(uint16_t log_number)
WITH_SEMAPHORE ( sem ) ;
if ( check_wrapped ( ) ) {
StartRead ( 1 ) ;
bottom = GetFileNumber ( ) ;
if ( is_wrapped ( ) ) {
bottom = StartRead ( 1 ) ;
if ( bottom > log_number ) {
bottom = find_last_page ( ) ;
top = df_NumPages ;
@ -601,43 +755,45 @@ uint32_t AP_Logger_Block::find_last_page_of_log(uint16_t log_number)
@@ -601,43 +755,45 @@ uint32_t AP_Logger_Block::find_last_page_of_log(uint16_t log_number)
}
}
StartRead ( top ) ;
if ( GetFileNumber ( ) = = log_number ) {
if ( StartRead ( top ) = = log_number ) {
return top ;
}
StartRead ( bottom ) ;
if ( GetFileNumber ( ) = = log_number ) {
if ( StartRead ( bottom ) = = log_number ) {
return bottom ;
}
gcs ( ) . send_text ( MAV_SEVERITY_ERROR , " No last page of log %d at top=%X or bot=%X " , int ( log_number ) , unsigned ( top ) , unsigned ( bottom ) ) ;
GCS_SEND_TEXT ( MAV_SEVERITY_ERROR , " No last page of log %d at top=%X or bot=%X " , int ( log_number ) , unsigned ( top ) , unsigned ( bottom ) ) ;
return 0 ;
}
void AP_Logger_Block : : get_log_info ( uint16_t log_num , uint32_t & size , uint32_t & time_utc )
void AP_Logger_Block : : get_log_info ( uint16_t list_entry , uint32_t & size , uint32_t & time_utc )
{
uint32_t start , end ;
WITH_SEMAPHORE ( sem ) ;
get_log_boundaries ( log_num , start , end ) ;
get_log_boundaries ( list_entry , start , end ) ;
if ( end > = start ) {
size = ( end + 1 - start ) * ( uint32_t ) df_PageSize ;
size = ( end + 1 - start ) * ( uint32_t ) ( df_PageSize - sizeof ( PageHeader ) ) ;
} else {
size = ( df_NumPages + end - start ) * ( uint32_t ) df_PageSize ;
size = ( df_NumPages + end + 1 - start ) * ( uint32_t ) ( df_PageSize - sizeof ( PageHeader ) ) ;
}
time_utc = 0 ;
}
size - = sizeof ( FileHeader ) ;
void AP_Logger_Block : : PrepForArming ( )
{
if ( logging_started ( ) ) {
return ;
//printf("LOG %d(%d), %d-%d, size %d\n", log_num_from_list_entry(list_entry), list_entry, start, end, size);
StartRead ( start ) ;
// the log we are currently writing
if ( df_FileTime = = 0 & & df_FileNumber = = df_Write_FileNumber ) {
uint64_t utc_usec ;
if ( AP : : rtc ( ) . get_utc_usec ( utc_usec ) ) {
df_FileTime = utc_usec / 1000000U ;
}
}
start_new_log ( ) ;
time_utc = df_FileTime ;
}
// read size bytes of data from the buffer
@ -647,18 +803,49 @@ bool AP_Logger_Block::BlockRead(uint16_t IntPageAdr, void *pBuffer, uint16_t siz
@@ -647,18 +803,49 @@ bool AP_Logger_Block::BlockRead(uint16_t IntPageAdr, void *pBuffer, uint16_t siz
return true ;
}
bool AP_Logger_Block : : logging_failed ( ) const
{
if ( ! _initialised ) {
return true ;
}
if ( ! io_thread_alive ( ) ) {
return true ;
}
if ( chip_full ) {
return true ;
}
return false ;
}
bool AP_Logger_Block : : io_thread_alive ( ) const
{
// if the io thread hasn't had a heartbeat in 5s it is dead
// the timeout is longer than might be otherwise required to allow for the FFT running
// at the same priority
return ( AP_HAL : : millis ( ) - io_timer_heartbeat ) < 5000U ;
}
/*
IO timer running on IO thread
The IO timer runs every 1 ms or at 1 Khz . The standard flash chip can write rougly 130 Kb / s
so there is little point in trying to write more than 130 bytes - or 1 page ( 256 bytes ) .
The W25Q128FV datasheet gives tpp as typically 0.7 ms yielding an absolute maximum rate of
365 Kb / s or just over a page per cycle .
*/
void AP_Logger_Block : : io_timer ( void )
{
if ( ! _initialised ) {
uint32_t tnow = AP_HAL : : millis ( ) ;
io_timer_heartbeat = tnow ;
// don't write anything for the first 2s to give the dataflash chip a chance to be ready
if ( ! _initialised | | tnow < 2000 ) {
return ;
}
WITH_SEMAPHORE ( sem ) ;
if ( erase_started ) {
WITH_SEMAPHORE ( sem ) ;
if ( InErase ( ) ) {
return ;
}
@ -669,11 +856,14 @@ void AP_Logger_Block::io_timer(void)
@@ -669,11 +856,14 @@ void AP_Logger_Block::io_timer(void)
memcpy ( buffer , & version , sizeof ( version ) ) ;
FinishWrite ( ) ;
erase_started = false ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Chip erase complete " ) ;
chip_full = false ;
status_msg = StatusMessage : : ERASE_COMPLETE ;
return ;
}
if ( df_EraseFrom > 0 ) {
WITH_SEMAPHORE ( sem ) ;
const uint32_t sectors = df_NumPages / df_PagePerSector ;
const uint32_t sectors_in_64k = 0x10000 / ( df_PagePerSector * df_PageSize ) ;
uint32_t next_sector = get_sector ( df_EraseFrom ) ;
@ -688,21 +878,38 @@ void AP_Logger_Block::io_timer(void)
@@ -688,21 +878,38 @@ void AP_Logger_Block::io_timer(void)
SectorErase ( next_sector / sectors_in_64k ) ;
next_sector + = sectors_in_64k ;
}
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Log recovery complete, erased %d blocks " , unsigned ( blocks_erased ) ) ;
status_msg = StatusMessage : : RECOVERY_COMPLETE ;
df_EraseFrom = 0 ;
}
if ( ! CardInserted ( ) | | ! log_write_started ) {
if ( ! CardInserted ( ) | | new_log_pending | | chip_full ) {
return ;
}
while ( writebuf . available ( ) > = df_PageSize - sizeof ( struct PageHeader ) ) {
struct PageHeader ph ;
ph . FileNumber = df_FileNumber ;
ph . FilePage = df_FilePage ;
memcpy ( buffer , & ph , sizeof ( ph ) ) ;
writebuf . read ( & buffer [ sizeof ( ph ) ] , df_PageSize - sizeof ( ph ) ) ;
FinishWrite ( ) ;
df_FilePage + + ;
// write at most one page
if ( writebuf . available ( ) > = df_PageSize - sizeof ( struct PageHeader ) ) {
WITH_SEMAPHORE ( sem ) ;
write_log_page ( ) ;
}
}
// write out a page of log data
void AP_Logger_Block : : write_log_page ( )
{
struct PageHeader ph ;
ph . FileNumber = df_Write_FileNumber ;
ph . FilePage = df_Write_FilePage ;
# if BLOCK_LOG_VALIDATE
ph . crc = DF_LOGGING_FORMAT + df_Write_FilePage ;
# endif
memcpy ( buffer , & ph , sizeof ( ph ) ) ;
const uint32_t pagesize = df_PageSize - sizeof ( ph ) ;
uint32_t nbytes = writebuf . read ( & buffer [ sizeof ( ph ) ] , pagesize ) ;
if ( nbytes < pagesize ) {
memset ( & buffer [ sizeof ( ph ) + nbytes ] , 0 , pagesize - nbytes ) ;
}
FinishWrite ( ) ;
df_Write_FilePage + + ;
}