-
Notifications
You must be signed in to change notification settings - Fork 73
Open
Description
The "bin file" logging will sometimes give a "Bad logging" error message in ArduPilot.
Typically happens after first arm then disarm, as mavlink-router sees no log messages for 5 seconds
and assumes a lost link. Then it tries to restart logging and triggers a stop (MAV_REMOTE_LOG_DATA_BLOCK_STOP
) in the process. ArduPilot
then interprets this as a logging backend failure for <0.5sec during the logging restart.
ArduPilot: ./libraries/AP_Logger/AP_logger_MAVLink.cpp:
AP_Logger_MAVLink::handle_ack
if(seqno == MAV_REMOTE_LOG_DATA_BLOCK_STOP) {
Debug("Received stop-logging packet");
stop_logging();
return;
}
void AP_Logger_MAVLink::stop_logging()
{
if (_sending_to_client) {
_sending_to_client = false;
_last_response_time = AP_HAL::millis();
}
}
bool AP_Logger_MAVLink::logging_failed() const
{
return !_sending_to_client;
}
mavlink-router: ./src/binlog.cpp:
void BinLog::_send_stop()
{
mavlink_message_t msg;
mavlink_msg_remote_log_block_status_pack(LOG_ENDPOINT_SYSTEM_ID,
MAV_COMP_ID_ALL,
&msg,
_target_system_id,
MAV_COMP_ID_ALL,
MAV_REMOTE_LOG_DATA_BLOCK_STOP,
1);
_send_msg(&msg, _target_system_id);
}
./src/logendpoint.cpp:
bool LogEndpoint::_alive_timeout()
{
if (_timeout_write_total == _stat.write.total) {
log_warning("No Log messages received in %u seconds restarting Log...", ALIVE_TIMEOUT);
stop();
start();
}
_timeout_write_total = _stat.write.total;
return true;
}
References:
https://mavlink.io/en/messages/ardupilotmega.html#MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
mavlink-router/mavlink-router#318
ArduPilot/ardupilot#19660
Metadata
Metadata
Assignees
Labels
No labels