联系作者 qq 843230304 ,欢迎交流分享
###QGroundControl无人机地面站 MAVLinkProtocol类,各个函数功能详解
###头文件MAVLinkProtocol.h
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#ifndef MAVLINKPROTOCOL_H_
#define MAVLINKPROTOCOL_H_
#include
#include
#include
#include
#include
#include
#include
#include
#include "LinkInterface.h"
#include "QGCMAVLink.h"
#include "QGC.h"
#include "QGCTemporaryFile.h"
#include "QGCToolbox.h"
class LinkManager;
class MultiVehicleManager;
class QGCApplication;
Q_DECLARE_LOGGING_CATEGORY(MAVLinkProtocolLog)
/**
* @brief MAVLink micro air vehicle protocol reference implementation.
*
* MAVLink is a generic communication protocol for micro air vehicles.
* for more information, please see the official website.
* @ref http://pixhawk.ethz.ch/software/mavlink/
**/
class MAVLinkProtocol : public QGCTool
{
Q_OBJECT
public:
MAVLinkProtocol(QGCApplication* app);
~MAVLinkProtocol();
/** @brief Get the human-friendly name of this protocol */
//获取协议名称
QString getName();
/** @brief Get the system id of this application */
//获取这个地面站的系统ID
int getSystemId();
/** @brief Get the component id of this application */
//获取组件ID
int getComponentId();
/** @brief Get protocol version check state */
//启用mav与qgc协议兼容检查
bool versionCheckEnabled() const {
return m_enable_version_check;
}
/** @brief Get the protocol version */
//获取当前qgc协议版本
int getVersion() {
return MAVLINK_VERSION;
}
/**
* Retrieve a total of all successfully parsed packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
* 检索指定链接的所有成功解析包的总数
* 返回 -1 表示没有可用的成功解析包
*/
qint32 getReceivedPacketCount(const LinkInterface *link) const {
return totalReceiveCounter[link->mavlinkChannel()];
}
/**
* Retrieve a total of all parsing errors for the specified link.
* @returns -1 if this is not available for this protocol, # of errors otherwise.
* 检索指定链接的所有解析错误
* 返回 -1 表示没有解析错误
*/
qint32 getParsingErrorCount(const LinkInterface *link) const {
return totalErrorCounter[link->mavlinkChannel()];
}
/**
* Retrieve a total of all dropped packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
* 检索指定链接的所有丢失包
* 返回 -1 表示没有丢失包
*/
qint32 getDroppedPacketCount(const LinkInterface *link) const {
return totalLossCounter[link->mavlinkChannel()];
}
/**
* Reset the counters for all metadata for this link.
* 为这个链接重置所有元数据的计数器
*/
virtual void resetMetadataForLink(const LinkInterface *link);
/// Suspend/Restart logging during replay.
/// 回放期间暂停/恢复日志
void suspendLogForReplay(bool suspend);
// Override from QGCTool
//设置所属工具
virtual void setToolbox(QGCToolbox *toolbox);
public slots:
/** @brief Receive bytes from a communication interface */
/// 从通信接口接收字节,解析协议
/// 它可以并行处理多个链接,每个链接都有自己的缓冲区和解析状态机
/// 这个函数跨线程
void receiveBytes(LinkInterface* link, QByteArray b);
/** @brief Set the system id of this application */
//设置系统ID
void setSystemId(int id);
/** @brief Enable / disable version check */
//启用/禁用版本检查
void enableVersionCheck(bool enabled);
/** @brief Load protocol settings */
//加载协议配置
void loadSettings();
/** @brief Store protocol settings */
//存储协议配置
void storeSettings();
#ifndef __mobile__
/// @brief Deletes any log files which are in the temp directory
/// 删除临时目录中的任何日志文件
static void deleteTempLogFiles(void);
/// Checks for lost log files
/// 检查丢失的日志文件
void checkForLostLogFiles(void);
#endif
protected:
///< Enable checking of version match of MAV and QGC
///启用mav与qgc协议兼容检查
bool m_enable_version_check;
///< Mutex to protect receiveBytes function
/// 保护接收字节函数
QMutex receiveMutex;
///< Store the last received sequence ID for each system/componenet pair
///存储每个 系统/组件 对 的最后一个接收序列ID
int lastIndex[256][256];
///< The total number of successfully received messages
///成功接收的消息总数
int totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS];
///< Total messages lost during transmission.
///在传输过程中丢失的消息总数
int totalLossCounter[MAVLINK_COMM_NUM_BUFFERS];
///< Total count of all parsing errors. Generally <= totalLossCounter.
///所有解析错误的总数。通常<=丢失的消息总数
int totalErrorCounter[MAVLINK_COMM_NUM_BUFFERS];
///< Received messages during this sample time window. Used for calculating loss %.
/// 在此示例时间窗口中 接收的消息。用于计算损失额
int currReceiveCounter[MAVLINK_COMM_NUM_BUFFERS];
///< Lost messages during this sample time window. Used for calculating loss %.
///在此示例时间窗口中 丢失的消息。用于计算损失额。
int currLossCounter[MAVLINK_COMM_NUM_BUFFERS];
///忽略mav与qgc的协议版本不匹配
bool versionMismatchIgnore;
///系统ID
int systemId;
signals:
/// Heartbeat received on link
//发出连接中收到的心跳包
void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType);
/** @brief Message received and directly copied via signal */
//发出连接中收到的消息
void messageReceived(LinkInterface* link, mavlink_message_t message);
/** @brief Emitted if version check is enabled / disabled */
//发出版本检查标志
void versionCheckChanged(bool enabled);
/** @brief Emitted if a message from the protocol should reach the user */
//发出协议状态消息
void protocolStatusMessage(const QString& title, const QString& message);
/** @brief Emitted if a new system ID was set */
//发出信号,新系统ID被设置
void systemIdChanged(int systemId);
///发出信号,接收丢失参数百分比改变
void receiveLossPercentChanged(int uasId, float lossPercent);
///发出信号,接收总丢失数据包改变
void receiveLossTotalChanged(int uasId, int totalLoss);
/**
* @brief Emitted if a new radio status packet received 发出信号,如果接收到一个新的遥控器状态数据包
*
* @param rxerrors receive errors rxerrors接收错误
* @param fixed count of error corrected packets fixed错误纠正数据包的计数
* @param rssi local signal strength in dBm rssi接收信号强度 dBm
* @param remrssi remote signal strength in dBm remrssi远程信号强度 dBm
* @param txbuf how full the tx buffer is as a percentage txbuf发送缓冲区的百分比
* @param noise background noise level noise背景噪声等级
* @param remnoise remote background noise level remnoise远程背景噪音等级
*/
void radioStatusChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi,
unsigned txbuf, unsigned noise, unsigned remnoise);
/// Emitted when a temporary telemetry log file is ready for saving
/// 发出信号,当一个临时的遥测日志文件准备保存时
void saveTelemetryLog(QString tempLogfile);
/// Emitted when a telemetry log is started to save.
/// 当遥测日志开始保存时发出
void checkTelemetrySavePath(void);
private slots:
///飞机数量改变
void _vehicleCountChanged(int count);
private:
#ifndef __mobile__
bool _closeLogFile(void);
void _startLogging(void);
void _stopLogging(void);
bool _logSuspendError; ///< true: Logging suspended due to error
bool _logSuspendReplay; ///< true: Logging suspended due to replay
bool _vehicleWasArmed; ///< true: Vehicle was armed during log sequence
QGCTemporaryFile _tempLogFile; ///< File to log to
static const char* _tempLogFileTemplate; ///< Template for temporary log file
static const char* _logFileExtension; ///< Extension for log files
#endif
LinkManager* _linkMgr;
MultiVehicleManager* _multiVehicleManager;
};
#endif // MAVLINKPROTOCOL_H_
###源文件MAVLinkProtocol.cc
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
/**
* @file
* @brief Implementation of class MAVLinkProtocol
* @author Lorenz Meier
*/
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASInterface.h"
#include "UAS.h"
#include "LinkManager.h"
#include "QGCMAVLink.h"
#include "QGC.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include "MultiVehicleManager.h"
#include "SettingsManager.h"
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
* the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
*/
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
: QGCTool(app)
, 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)
{
memset(&totalReceiveCounter, 0, sizeof(totalReceiveCounter));
memset(&totalLossCounter, 0, sizeof(totalLossCounter));
memset(&totalErrorCounter, 0, sizeof(totalErrorCounter));
memset(&currReceiveCounter, 0, sizeof(currReceiveCounter));
memset(&currLossCounter, 0, sizeof(currLossCounter));
}
MAVLinkProtocol::~MAVLinkProtocol()
{
storeSettings();
#ifndef __mobile__
_closeLogFile();
#endif
}
void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
{
QGCTool::setToolbox(toolbox);
_linkMgr = _toolbox->linkManager();
_multiVehicleManager = _toolbox->multiVehicleManager();
qRegisterMetaType("mavlink_message_t");
loadSettings();
// All the *Counter variables are not initialized here, as they should be initialized
// on a per-link basis before those links are used. @see resetMetadataForLink().
// Initialize the list for tracking dropped messages to invalid.
for (int i = 0; i < 256; i++)
{
for (int j = 0; j < 256; j++)
{
lastIndex[i][j] = -1;
}
}
//协议状态消息,发送到消息提示
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);
//发出信号,协议版本检查标志
emit versionCheckChanged(m_enable_version_check);
}
void MAVLinkProtocol::loadSettings()
{
// Load defaults from settings
QSettings settings;
settings.beginGroup("QGC_MAVLINK_PROTOCOL");
enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
// Only set system id if it was valid
int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
if (temp > 0 && temp < 256)
{
systemId = temp;
}
}
void MAVLinkProtocol::storeSettings()
{
// Store settings
QSettings settings;
settings.beginGroup("QGC_MAVLINK_PROTOCOL");
settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
settings.setValue("GCS_SYSTEM_ID", systemId);
// Parameter interface settings
}
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
int channel = link->mavlinkChannel();
totalReceiveCounter[channel] = 0;
totalLossCounter[channel] = 0;
totalErrorCounter[channel] = 0;
currReceiveCounter[channel] = 0;
currLossCounter[channel] = 0;
}
/**
* 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/
* parsing state machine.
* @param link The interface to read from
* @see LinkInterface
*
* 它可以并行处理多个链接,每个链接都有自己的缓冲区和解析状态机
* 这个函数跨线程
**/
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
// Since receiveBytes signals cross threads we can end up with signals in the queue
// that come through after the link is disconnected. For these we just drop the data
// since the link is closed.
if (!_linkMgr->containsLink(link)) {
return;
}
// receiveMutex.lock();
mavlink_message_t message;
mavlink_status_t status;
int mavlinkChannel = link->mavlinkChannel();
static int nonmavlinkCount = 0;
static bool checkedUserNonMavlink = false;
static bool warnedUserNonMavlink = false;
//遍历接收缓冲区
for (int position = 0; position < b.size(); position++) {
/** decodeState 是 mavlink_framing_t 中的枚举值
* typedef enum {
MAVLINK_FRAMING_INCOMPLETE=0, //mavlink数据包不完整
MAVLINK_FRAMING_OK=1, //解析mavlink包成功
MAVLINK_FRAMING_BAD_CRC=2, //错误的crc校验
MAVLINK_FRAMING_BAD_SIGNATURE=3 //错误的包签名
} mavlink_framing_t;
*/
//该函数将一次解析一个字节,并一次返回完整的包,mavlink包放在message,状态放在status
unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
//mavlink数据包不完整,并且不是已经解析了第一个mavlink数据包
if (decodeState == 0 && !link->decodedFirstMavlinkPacket())
{
nonmavlinkCount++;
//连续2000个字节没有检查到mavlink包,并且没有警告过用户“没有mavlink消息”
if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
{
//2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
if (!checkedUserNonMavlink)
{
link->requestReset();
checkedUserNonMavlink = true;
}
else
{
//警告用户没有mavlink消息,并且置标志位
warnedUserNonMavlink = true;
emit protocolStatusMessage(tr("MAVLink Protocol"), tr("There is a MAVLink Version or Baud Rate Mismatch. "
"Please check if the baud rates of %1 and your autopilot are the same.").arg(qgcApp()->applicationName()));
}
}
}
//解析mavlink包成功
if (decodeState == 1)
{
//没有解码第一个mavlink包
if (!link->decodedFirstMavlinkPacket()) {
mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
//不是mavlink1.0协议,切换到mavlink2.0协议
if (!(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
qDebug() << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
//设置标志位,解码第一个mavlink包
link->setDecodedFirstMavlinkPacket(true);
}
//解码遥控器状态
if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
{
// process telemetry status message
mavlink_radio_status_t rstatus;
mavlink_msg_radio_status_decode(&message, &rstatus);
int rssi = rstatus.rssi,
remrssi = rstatus.remrssi;
// 3DR Si1k radio needs rssi fields to be converted to dBm
if (message.sysid == '3' && message.compid == 'D') {
/* Per the Si1K datasheet figure 23.25 and SI AN474 code
* samples the relationship between the RSSI register
* and received power is as follows:
*
* 10
* inputPower = rssi * ------ 127
* 19
*
* Additionally limit to the only realistic range [-120,0] dBm
*/
rssi = qMin(qMax(qRound(static_cast(rssi) / 1.9 - 127.0), - 120), 0);
remrssi = qMin(qMax(qRound(static_cast(remrssi) / 1.9 - 127.0), - 120), 0);
} else {
rssi = (int8_t) rstatus.rssi;
remrssi = (int8_t) rstatus.remrssi;
}
emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rssi, remrssi,
rstatus.txbuf, rstatus.noise, rstatus.remnoise);
}
#ifndef __mobile__
// Log data
// 记录日志
if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)];
// Write the uint64 time in microseconds in big endian format before the message.
// This timestamp is saved in UTC time. We are only saving in ms precision because
// getting more than this isn't possible with Qt without a ton of extra code.
quint64 time = (quint64)QDateTime::currentMSecsSinceEpoch() * 1000;
qToBigEndian(time, buf);
// Then write the message to the buffer
int len = mavlink_msg_to_send_buffer(buf + sizeof(quint64), &message);
// Determine how many bytes were written by adding the timestamp size to the message size
len += sizeof(quint64);
// Now write this timestamp/message pair to the log.
QByteArray b((const char*)buf, len);
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;
}
// Check for the vehicle arming going by. This is used to trigger log save.
if (!_vehicleWasArmed && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
mavlink_heartbeat_t state;
mavlink_msg_heartbeat_decode(&message, &state);
if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
_vehicleWasArmed = true;
}
}
}
#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);
}
// Increase receive counter
//增加接收计数器
totalReceiveCounter[mavlinkChannel]++;
currReceiveCounter[mavlinkChannel]++;
// Determine what the next expected sequence number is, accounting for
// never having seen a message for this system/component pair.
//确定下一个包序号
int lastSeq = lastIndex[message.sysid][message.compid];
int expectedSeq = (lastSeq == -1) ? message.seq : (lastSeq + 1);
// And if we didn't encounter that sequence number, record the error
//如果我们没有遇到那个包序列号,记录错误
if (message.seq != expectedSeq)
{
// Determine how many messages were skipped
// 确定丢失了多少条消息
int lostMessages = message.seq - expectedSeq;
// Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
if (lostMessages < 0)
{
lostMessages = 0;
}
// And log how many were lost for all time and just this timestep
//记录下有多少mavlink连接在这一时刻丢失包
totalLossCounter[mavlinkChannel] += lostMessages;
currLossCounter[mavlinkChannel] += lostMessages;
}
// And update the last sequence number for this system/component pair
// 更新最后一个包序号,为这个 系统/组件 对
lastIndex[message.sysid][message.compid] = expectedSeq;
// Update on every 32th packet
// 每32个包更新统计
if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
{
// Calculate new loss ratio
// Receive loss
// 重新计算丢包率
float receiveLossPercent = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
receiveLossPercent *= 100.0f;
currLossCounter[mavlinkChannel] = 0;
currReceiveCounter[mavlinkChannel] = 0;
emit receiveLossPercentChanged(message.sysid, receiveLossPercent);
emit receiveLossTotalChanged(message.sysid, totalLossCounter[mavlinkChannel]);
}
// The packet is emitted as a whole, as it is only 255 - 261 bytes short
// kind of inefficient, but no issue for a groundstation pc.
// It buys as reentrancy for the whole code over all threads
// 数据包是作为一个整体发出的,因为它只有255 - 261字节效率损失
// 但对于一个运行于PC的地面站来说,没有问题
// 它以所有线程的整个代码为可重入
// 把整个mavlink包发送出去,提供其他需要mavlink包的模块解析
emit messageReceived(link, message);
}
}
}
/**
* @return The name of this protocol
**/
QString MAVLinkProtocol::getName()
{
return QString(tr("MAVLink protocol"));
}
/** @return System id of this application */
int MAVLinkProtocol::getSystemId()
{
return systemId;
}
void MAVLinkProtocol::setSystemId(int id)
{
systemId = id;
}
/** @return Component id of this application */
int MAVLinkProtocol::getComponentId()
{
return 0;
}
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
m_enable_version_check = enabled;
emit versionCheckChanged(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)
{
if (_tempLogFile.isOpen()) {
if (_tempLogFile.size() == 0) {
// Don't save zero byte files
_tempLogFile.remove();
return false;
} else {
_tempLogFile.flush();
_tempLogFile.close();
return true;
}
}
return false;
}
void MAVLinkProtocol::_startLogging(void)
{
if (qgcApp()->runningUnitTests()) {
return;
}
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();
emit checkTelemetrySavePath();
_logSuspendError = false;
}
}
}
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());
}
}
_vehicleWasArmed = false;
}
/// @brief Checks the temp directory for log files which may have been left there.
/// This could happen if QGC crashes without the temp log file being saved.
/// Give the user an option to save these orphaned files.
void MAVLinkProtocol::checkForLostLogFiles(void)
{
QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QString filter(QString("*.%1").arg(_logFileExtension));
QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
qDebug() << "Orphaned log file count" << fileInfoList.count();
foreach(const QFileInfo fileInfo, fileInfoList) {
qDebug() << "Orphaned log file" << fileInfo.filePath();
if (fileInfo.size() == 0) {
// Delete all zero length files
QFile::remove(fileInfo.filePath());
continue;
}
emit saveTelemetryLog(fileInfo.filePath());
}
}
void MAVLinkProtocol::suspendLogForReplay(bool suspend)
{
_logSuspendReplay = suspend;
}
void MAVLinkProtocol::deleteTempLogFiles(void)
{
QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QString filter(QString("*.%1").arg(_logFileExtension));
QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
foreach(const QFileInfo fileInfo, fileInfoList) {
QFile::remove(fileInfo.filePath());
}
}
#endif