Commit bd42dc42 authored by Don Gagne's avatar Don Gagne

Merge pull request #2168 from DonLakeFlyer/HeartbeatLogging

Start logging on heartbeat
parents d6288eeb ef6971a2
...@@ -198,13 +198,6 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) ...@@ -198,13 +198,6 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
// Use the same shared pointer as LinkManager // Use the same shared pointer as LinkManager
_connectedLinks.append(_linkMgr->sharedPointerForLink(link)); _connectedLinks.append(_linkMgr->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 // Send command to start MAVLink
// XXX hacky but safe // XXX hacky but safe
// Start NSH // Start NSH
...@@ -364,6 +357,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -364,6 +357,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
#endif #endif
if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
#ifndef __mobile__
// Start loggin on first heartbeat
_startLogging();
#endif
// Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed. // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
mavlink_heartbeat_t heartbeat; mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat); mavlink_msg_heartbeat_decode(&message, &heartbeat);
...@@ -657,8 +655,7 @@ bool MAVLinkProtocol::_closeLogFile(void) ...@@ -657,8 +655,7 @@ bool MAVLinkProtocol::_closeLogFile(void)
void MAVLinkProtocol::_startLogging(void) void MAVLinkProtocol::_startLogging(void)
{ {
Q_ASSERT(!_tempLogFile.isOpen()); if (!_tempLogFile.isOpen()) {
if (!_logSuspendReplay) { if (!_logSuspendReplay) {
if (!_tempLogFile.open()) { if (!_tempLogFile.open()) {
emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. " emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. "
...@@ -672,6 +669,7 @@ void MAVLinkProtocol::_startLogging(void) ...@@ -672,6 +669,7 @@ void MAVLinkProtocol::_startLogging(void)
_logSuspendError = false; _logSuspendError = false;
} }
}
} }
void MAVLinkProtocol::_stopLogging(void) void MAVLinkProtocol::_stopLogging(void)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment