From 2d6a09546b4dd68d309d4442d033fb41dfce9869 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 27 Oct 2015 17:29:54 -0700 Subject: [PATCH] Revert "Start logging on heartbeat instead of connect" --- src/comm/MAVLinkProtocol.cc | 36 +++++++++++++++++++----------------- 1 file changed, 19 insertions(+), 17 deletions(-) diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index deadbd219..d221dc26e 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -187,6 +187,13 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) // Use the same shared pointer as LinkManager _connectedLinks.append(LinkManager::instance()->sharedPointerForLink(link)); +#ifndef __mobile__ + if (_connectedLinks.count() == 1) { + // This is the first link, we need to start logging + _startLogging(); + } +#endif + // Send command to start MAVLink // XXX hacky but safe // Start NSH @@ -346,11 +353,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) #endif if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { -#ifndef __mobile__ - // Start logging on first heartbeat - _startLogging(); -#endif - // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed. mavlink_heartbeat_t heartbeat; mavlink_msg_heartbeat_decode(&message, &heartbeat); @@ -644,20 +646,20 @@ bool MAVLinkProtocol::_closeLogFile(void) void MAVLinkProtocol::_startLogging(void) { - if (!_tempLogFile.isOpen()) { - if (!_logSuspendReplay) { - if (!_tempLogFile.open()) { - emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. " - "Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName())); - _closeLogFile(); - _logSuspendError = true; - return; - } - - qDebug() << "Temp log" << _tempLogFile.fileName(); + Q_ASSERT(!_tempLogFile.isOpen()); - _logSuspendError = false; + if (!_logSuspendReplay) { + if (!_tempLogFile.open()) { + emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. " + "Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName())); + _closeLogFile(); + _logSuspendError = true; + return; } + + qDebug() << "Temp log" << _tempLogFile.fileName(); + + _logSuspendError = false; } } -- 2.22.0