diff --git a/src/comm/BluetoothLink.cc b/src/comm/BluetoothLink.cc index 320c4a4140107971afd74a24e289fc31a2acc998..52295790bbb3db837c5c17f483eda832e8bc3c12 100644 --- a/src/comm/BluetoothLink.cc +++ b/src/comm/BluetoothLink.cc @@ -78,6 +78,7 @@ void BluetoothLink::_writeBytes(const QByteArray bytes) { if (_targetSocket) { if(_targetSocket->write(bytes) > 0) { + emit bytesSent(this, bytes); _logOutputDataRate(bytes.size(), QDateTime::currentMSecsSinceEpoch()); } else { qWarning() << "Bluetooth write error"; diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index e04ecc4ffd776fd03e6524f5fbfa1c84df1720af..2af1f66ce898d3231795abb2223653fbf1e5d856 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -181,6 +181,16 @@ signals: */ void bytesReceived(LinkInterface* link, QByteArray data); + /** + * @brief New data has been sent + * * + * The new data is contained in the QByteArray data. + * The data is logged into telemetry logging system + * + * @param data the new bytes + */ + void bytesSent(LinkInterface* link, QByteArray data); + /** * @brief This signal is emitted instantly when the link is connected **/ diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index caa4d09230c4f72fc0ff75bcbe537b5e928f5b0f..7ca89eb1767dfceb87205bffc69f379c8cf4b799 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -199,6 +199,7 @@ void LinkManager::_addLink(LinkInterface* link) connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); + connect(link, &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes); _mavlinkProtocol->resetMetadataForLink(link); _mavlinkProtocol->setVersion(_mavlinkProtocol->getCurrentVersion()); diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index f5a52d11bb74f66b4c197b685470ec8e1c38d634..5e43702c96d2b08dec0d2664e1570d231d8cf529 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -159,6 +159,38 @@ void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link) link->setDecodedFirstMavlinkPacket(false); } +/** + * This method parses all outcoming bytes and log a MAVLink packet. + * @param link The interface to read from + * @see LinkInterface + **/ + +void MAVLinkProtocol::logSentBytes(LinkInterface* link, QByteArray b){ + + uint8_t bytes_time[sizeof(quint64)]; + + Q_UNUSED(link); + if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) { + + quint64 time = static_cast(QDateTime::currentMSecsSinceEpoch() * 1000); + + qToBigEndian(time,bytes_time); + + b.insert(0,QByteArray((const char*)bytes_time,sizeof(bytes_time))); + + int len = b.count(); + + if(_tempLogFile.write(b) != len) + { + // If there's an error logging data, raise an alert and stop logging. + emit protocolStatusMessage(tr("MAVLink Protocol"), tr("MAVLink Logging failed. Could not write to file %1, logging disabled.").arg(_tempLogFile.fileName())); + _stopLogging(); + _logSuspendError = true; + } + } + +} + /** * This method parses all incoming bytes and constructs a MAVLink packet. * It can handle multiple links in parallel, as each link has it's own buffer/ diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index 7614ee658be9cad6ab00a638b427fae155de7024..06a155ac32d0625b6c123dae5484d01aae17a546 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -81,6 +81,9 @@ public: public slots: /** @brief Receive bytes from a communication interface */ void receiveBytes(LinkInterface* link, QByteArray b); + + /** @brief Log bytes sent from a communication interface */ + void logSentBytes(LinkInterface* link, QByteArray b); /** @brief Set the system id of this application */ void setSystemId(int id); diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 46e5bfeaf2498636e2fa0d10c729a14655fa4abf..3625ac5eebd3dbec7e0ba5eb91f290ab304c831c 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -84,6 +84,7 @@ bool SerialLink::_isBootloader() void SerialLink::_writeBytes(const QByteArray data) { if(_port && _port->isOpen()) { + emit bytesSent(this, data); _logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch()); _port->write(data); } else { diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index dddbf76cb64c09340db0d12d2af1ec1a9e44ef82..82dd895ca82ac10c85c61e87f00b9a9ec649c7c9 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -81,6 +81,7 @@ void TCPLink::_writeBytes(const QByteArray data) if (_socket) { _socket->write(data); + emit bytesSent(this, data); _logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch()); } } diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 1642b9d92fca1dba7b634d578df163d69db75a0b..19db3085703948a543a22416c42f526d50b75c2d 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -169,6 +169,7 @@ void UDPLink::_writeBytes(const QByteArray data) if (!_socket) { return; } + emit bytesSent(this, data); // Send to all manually targeted systems for(UDPCLient* target: _udpConfig->targetHosts()) { // Skip it if it's part of the session clients below