AP_Logger: do not log soon after file transfer unless we're armed

mavlink log reads fail randomly, and you end up with a very large number
of log files as we keep closing logs off and then discovering we should
be logging
This commit is contained in:
Peter Barker 2021-03-20 08:28:29 +11:00 committed by Peter Barker
parent d9501766c7
commit 82a28e2a58
3 changed files with 15 additions and 0 deletions

View File

@ -554,6 +554,9 @@ private:
SENDING, // actively sending log_sending packets
} transfer_activity = TransferActivity::IDLE;
// last time we handled a log-transfer-over-mavlink message:
uint32_t _last_mavlink_log_transfer_message_handled_ms;
// next log list entry to send
uint16_t _log_next_list_entry;

View File

@ -429,6 +429,17 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical)
return false;
}
if (_front._last_mavlink_log_transfer_message_handled_ms != 0) {
if (AP_HAL::millis() - _front._last_mavlink_log_transfer_message_handled_ms < 10000) {
if (!_front.vehicle_is_armed()) {
// user is transfering files via mavlink
return false;
}
} else {
_front._last_mavlink_log_transfer_message_handled_ms = 0;
}
}
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

View File

@ -45,6 +45,7 @@ void AP_Logger::handle_log_message(GCS_MAVLINK &link, const mavlink_message_t &m
if (!should_handle_log_message()) {
return;
}
_last_mavlink_log_transfer_message_handled_ms = AP_HAL::millis();
switch (msg.msgid) {
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
handle_log_request_list(link, msg);