DataFlash: log critical messages while disarmed

this logs critical messages while disarmed if we have logged any
messages while armed. This fixes issue #7010 where log files show the
incorrect mode if the log includes any portions where the user
disarmed. It makes analysing users logs very difficult. It also
affects parameters, so we don't always know the true parameter values
in logs from users.
This commit is contained in:
Andrew Tridgell 2017-10-26 16:29:09 +11:00
parent 2d684cd9e8
commit 3126dea51d
2 changed files with 19 additions and 7 deletions

View File

@ -285,7 +285,7 @@ bool DataFlash_Backend::StartNewLogOK() const
bool DataFlash_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
{
if (!ShouldLog()) {
if (!ShouldLog(is_critical)) {
return false;
}
if (StartNewLogOK()) {
@ -297,14 +297,11 @@ bool DataFlash_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size
return _WritePrioritisedBlock(pBuffer, size, is_critical);
}
bool DataFlash_Backend::ShouldLog() const
bool DataFlash_Backend::ShouldLog(bool is_critical)
{
if (!_front.WritesEnabled()) {
return false;
}
if (!_front.vehicle_is_armed() && !_front.log_while_disarmed()) {
return false;
}
if (!_initialised) {
return false;
}
@ -315,5 +312,20 @@ bool DataFlash_Backend::ShouldLog() const
return false;
}
if (is_critical && have_logged_armed && !_front._params.file_disarm_rot) {
// if we have previously logged while armed then we log all
// critical messages from then on. That fixes a problem where
// logs show the wrong flight mode if you disarm then arm again
return true;
}
if (!_front.vehicle_is_armed() && !_front.log_while_disarmed()) {
return false;
}
if (_front.vehicle_is_armed()) {
have_logged_armed = true;
}
return true;
}

View File

@ -138,7 +138,7 @@ protected:
print_mode_fn print_mode,
AP_HAL::BetterStream *port);
bool ShouldLog() const;
bool ShouldLog(bool is_critical);
virtual bool WritesOK() const = 0;
virtual bool StartNewLogOK() const;
@ -168,5 +168,5 @@ private:
uint32_t _last_periodic_1Hz;
uint32_t _last_periodic_10Hz;
bool have_logged_armed;
};