|
|
@ -57,7 +57,7 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app) |
|
|
|
#ifndef __mobile__ |
|
|
|
#ifndef __mobile__ |
|
|
|
, _logSuspendError(false) |
|
|
|
, _logSuspendError(false) |
|
|
|
, _logSuspendReplay(false) |
|
|
|
, _logSuspendReplay(false) |
|
|
|
, _logPromptForSave(false) |
|
|
|
, _vehicleWasArmed(false) |
|
|
|
, _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)) |
|
|
|
, _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)) |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
, _linkMgr(NULL) |
|
|
|
, _linkMgr(NULL) |
|
|
@ -283,11 +283,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// Check for the vehicle arming going by. This is used to trigger log save.
|
|
|
|
// Check for the vehicle arming going by. This is used to trigger log save.
|
|
|
|
if (!_logPromptForSave && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { |
|
|
|
if (!_vehicleWasArmed && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { |
|
|
|
mavlink_heartbeat_t state; |
|
|
|
mavlink_heartbeat_t state; |
|
|
|
mavlink_msg_heartbeat_decode(&message, &state); |
|
|
|
mavlink_msg_heartbeat_decode(&message, &state); |
|
|
|
if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) { |
|
|
|
if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) { |
|
|
|
_logPromptForSave = true; |
|
|
|
_vehicleWasArmed = true; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -429,11 +429,7 @@ void MAVLinkProtocol::_startLogging(void) |
|
|
|
return; |
|
|
|
return; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if (_app->promptFlightDataSaveNotArmed()) { |
|
|
|
qDebug() << "Temp log" << _tempLogFile.fileName(); |
|
|
|
_logPromptForSave = true; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
qDebug() << "Temp log" << _tempLogFile.fileName() << _logPromptForSave; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
_logSuspendError = false; |
|
|
|
_logSuspendError = false; |
|
|
|
} |
|
|
|
} |
|
|
@ -444,13 +440,13 @@ void MAVLinkProtocol::_stopLogging(void) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (_closeLogFile()) { |
|
|
|
if (_closeLogFile()) { |
|
|
|
// If the signals are not connected it means we are running a unit test. In that case just delete log files
|
|
|
|
// If the signals are not connected it means we are running a unit test. In that case just delete log files
|
|
|
|
if (_logPromptForSave && _app->promptFlightDataSave()) { |
|
|
|
if ((_vehicleWasArmed || _app->promptFlightDataSaveNotArmed()) && _app->promptFlightDataSave()) { |
|
|
|
emit saveTempFlightDataLog(_tempLogFile.fileName()); |
|
|
|
emit saveTempFlightDataLog(_tempLogFile.fileName()); |
|
|
|
} else { |
|
|
|
} else { |
|
|
|
QFile::remove(_tempLogFile.fileName()); |
|
|
|
QFile::remove(_tempLogFile.fileName()); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
_logPromptForSave = false; |
|
|
|
_vehicleWasArmed = false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/// @brief Checks the temp directory for log files which may have been left there.
|
|
|
|
/// @brief Checks the temp directory for log files which may have been left there.
|
|
|
|