diff --git a/libraries/DataFlash/DataFlash.cpp b/libraries/DataFlash/DataFlash.cpp index 70040b4959e55..4fb81123f0742 100644 --- a/libraries/DataFlash/DataFlash.cpp +++ b/libraries/DataFlash/DataFlash.cpp @@ -265,6 +265,19 @@ void DataFlash_Class::Log_Write_MessageF(const char *fmt, ...) Log_Write_Message(msg); } +void DataFlash_Class::backend_starting_new_log(const DataFlash_Backend *backend) +{ + for (uint8_t i=0; i<_next_backend; i++) { + if (backends[i] == backend) { // pointer comparison! + // reset sent masks + for (struct log_write_fmt *f = log_write_fmts; f; f=f->next) { + f->sent_mask &= ~(1<reset(); + _front.backend_starting_new_log(this); } void DataFlash_Backend::internal_error() { diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 1606d0b9402ab..07ea2bce4936e 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -584,15 +584,14 @@ void DataFlash_Block::ListAvailableLogs(AP_HAL::BetterStream *port) // This function starts a new log file in the DataFlash, and writes // the format of supported messages in the log +// This function is ONLY called from the vehicle code. +// DataFlash_MAVLink, for example, will NOT call this function if the +// remote end disconnects and reconnects! void DataFlash_Class::StartNewLog(void) { for (uint8_t i=0; i<_next_backend; i++) { backends[i]->start_new_log(); } - // reset sent masks - for (struct log_write_fmt *f = log_write_fmts; f; f=f->next) { - f->sent_mask = 0; - } } /*