@ -41,10 +41,8 @@ Q_DECLARE_METATYPE(mavlink_message_t)
@@ -41,10 +41,8 @@ Q_DECLARE_METATYPE(mavlink_message_t)
QGC_LOGGING_CATEGORY ( MAVLinkProtocolLog , " MAVLinkProtocolLog " )
# ifndef __mobile__
const char * MAVLinkProtocol : : _tempLogFileTemplate = " FlightDataXXXXXX " ; ///< Template for temporary log file
const char * MAVLinkProtocol : : _logFileExtension = " mavlink " ; ///< Extension for log files
# endif
/**
* The default constructor will create a new MAVLink object sending heartbeats at
@ -55,12 +53,10 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
@@ -55,12 +53,10 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
, m_enable_version_check ( true )
, versionMismatchIgnore ( false )
, systemId ( 255 )
# ifndef __mobile__
, _logSuspendError ( false )
, _logSuspendReplay ( false )
, _vehicleWasArmed ( false )
, _tempLogFile ( QString ( " %2.%3 " ) . arg ( _tempLogFileTemplate ) . arg ( _logFileExtension ) )
# endif
, _linkMgr ( NULL )
, _multiVehicleManager ( NULL )
{
@ -74,10 +70,7 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
@@ -74,10 +70,7 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
MAVLinkProtocol : : ~ MAVLinkProtocol ( )
{
storeSettings ( ) ;
# ifndef __mobile__
_closeLogFile ( ) ;
# endif
}
void MAVLinkProtocol : : setToolbox ( QGCToolbox * toolbox )
@ -104,10 +97,8 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
@@ -104,10 +97,8 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
}
connect ( this , & MAVLinkProtocol : : protocolStatusMessage , _app , & QGCApplication : : criticalMessageBoxOnMainThread ) ;
# ifndef __mobile__
connect ( this , & MAVLinkProtocol : : saveTelemetryLog , _app , & QGCApplication : : saveTelemetryLogOnMainThread ) ;
connect ( this , & MAVLinkProtocol : : checkTelemetrySavePath , _app , & QGCApplication : : checkTelemetrySavePathOnMainThread ) ;
# endif
connect ( _multiVehicleManager - > vehicles ( ) , & QmlObjectListModel : : countChanged , this , & MAVLinkProtocol : : _vehicleCountChanged ) ;
@ -208,9 +199,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -208,9 +199,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
link - > setDecodedFirstMavlinkPacket ( true ) ;
}
# ifndef __mobile__
// Log data
if ( ! _logSuspendError & & ! _logSuspendReplay & & _tempLogFile . isOpen ( ) ) {
uint8_t buf [ MAVLINK_MAX_PACKET_LEN + sizeof ( quint64 ) ] ;
@ -245,14 +234,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -245,14 +234,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
}
}
}
# endif
if ( message . msgid = = MAVLINK_MSG_ID_HEARTBEAT ) {
# ifndef __mobile__
// Start loggin on first heartbeat
_startLogging ( ) ;
# endif
mavlink_heartbeat_t heartbeat ;
mavlink_msg_heartbeat_decode ( & message , & heartbeat ) ;
emit vehicleHeartbeatInfo ( link , message . sysid , message . compid , heartbeat . mavlink_version , heartbeat . autopilot , heartbeat . type ) ;
@ -342,17 +327,12 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled)
@@ -342,17 +327,12 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled)
void MAVLinkProtocol : : _vehicleCountChanged ( int count )
{
# ifndef __mobile__
if ( count = = 0 ) {
// Last vehicle is gone, close out logging
_stopLogging ( ) ;
}
# else
Q_UNUSED ( count ) ;
# endif
}
# ifndef __mobile__
/// @brief Closes the log file if it is open
bool MAVLinkProtocol : : _closeLogFile ( void )
{
@ -367,16 +347,23 @@ bool MAVLinkProtocol::_closeLogFile(void)
@@ -367,16 +347,23 @@ bool MAVLinkProtocol::_closeLogFile(void)
return true ;
}
}
return false ;
}
void MAVLinkProtocol : : _startLogging ( void )
{
//-- Are we supposed to write logs?
if ( qgcApp ( ) - > runningUnitTests ( ) ) {
return ;
}
# ifdef __mobile__
//-- Mobile build don't write to /tmp unless told to do so
if ( ! _app - > toolbox ( ) - > settingsManager ( ) - > appSettings ( ) - > telemetrySave ( ) - > rawValue ( ) . toBool ( ) ) {
return ;
}
# endif
//-- Log is always written to a temp file. If later the user decides they want
// it, it's all there for them.
if ( ! _tempLogFile . isOpen ( ) ) {
if ( ! _logSuspendReplay ) {
if ( ! _tempLogFile . open ( ) ) {
@ -397,12 +384,14 @@ void MAVLinkProtocol::_startLogging(void)
@@ -397,12 +384,14 @@ void MAVLinkProtocol::_startLogging(void)
void MAVLinkProtocol : : _stopLogging ( void )
{
if ( _closeLogFile ( ) ) {
SettingsManager * settingsManager = _app - > toolbox ( ) - > settingsManager ( ) ;
if ( ( _vehicleWasArmed | | settingsManager - > appSettings ( ) - > telemetrySaveNotArmed ( ) - > rawValue ( ) . toBool ( ) ) & & settingsManager - > appSettings ( ) - > telemetrySave ( ) - > rawValue ( ) . toBool ( ) ) {
emit saveTelemetryLog ( _tempLogFile . fileName ( ) ) ;
} else {
QFile : : remove ( _tempLogFile . fileName ( ) ) ;
if ( _tempLogFile . isOpen ( ) ) {
if ( _closeLogFile ( ) ) {
if ( ( _vehicleWasArmed | | _app - > toolbox ( ) - > settingsManager ( ) - > appSettings ( ) - > telemetrySaveNotArmed ( ) - > rawValue ( ) . toBool ( ) ) & &
_app - > toolbox ( ) - > settingsManager ( ) - > appSettings ( ) - > telemetrySave ( ) - > rawValue ( ) . toBool ( ) ) {
emit saveTelemetryLog ( _tempLogFile . fileName ( ) ) ;
} else {
QFile : : remove ( _tempLogFile . fileName ( ) ) ;
}
}
}
_vehicleWasArmed = false ;
@ -426,7 +415,6 @@ void MAVLinkProtocol::checkForLostLogFiles(void)
@@ -426,7 +415,6 @@ void MAVLinkProtocol::checkForLostLogFiles(void)
QFile : : remove ( fileInfo . filePath ( ) ) ;
continue ;
}
emit saveTelemetryLog ( fileInfo . filePath ( ) ) ;
}
}
@ -447,4 +435,4 @@ void MAVLinkProtocol::deleteTempLogFiles(void)
@@ -447,4 +435,4 @@ void MAVLinkProtocol::deleteTempLogFiles(void)
QFile : : remove ( fileInfo . filePath ( ) ) ;
}
}
# endif