|
|
|
@ -61,14 +61,13 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
@@ -61,14 +61,13 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
|
|
|
|
|
, _logSuspendReplay(false) |
|
|
|
|
, _vehicleWasArmed(false) |
|
|
|
|
, _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)) |
|
|
|
|
, _linkMgr(NULL) |
|
|
|
|
, _multiVehicleManager(NULL) |
|
|
|
|
, _linkMgr(nullptr) |
|
|
|
|
, _multiVehicleManager(nullptr) |
|
|
|
|
{ |
|
|
|
|
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)); |
|
|
|
|
memset(totalReceiveCounter, 0, sizeof(totalReceiveCounter)); |
|
|
|
|
memset(totalLossCounter, 0, sizeof(totalLossCounter)); |
|
|
|
|
memset(runningLossPercent, 0, sizeof(runningLossPercent)); |
|
|
|
|
memset(firstMessage, 1, sizeof(firstMessage)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
MAVLinkProtocol::~MAVLinkProtocol() |
|
|
|
@ -109,15 +108,6 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
@@ -109,15 +108,6 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
|
|
|
|
|
// 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); |
|
|
|
|
connect(this, &MAVLinkProtocol::saveTelemetryLog, _app, &QGCApplication::saveTelemetryLogOnMainThread); |
|
|
|
|
connect(this, &MAVLinkProtocol::checkTelemetrySavePath, _app, &QGCApplication::checkTelemetrySavePathOnMainThread); |
|
|
|
@ -157,10 +147,11 @@ void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link)
@@ -157,10 +147,11 @@ void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link)
|
|
|
|
|
{ |
|
|
|
|
int channel = link->mavlinkChannel(); |
|
|
|
|
totalReceiveCounter[channel] = 0; |
|
|
|
|
totalLossCounter[channel] = 0; |
|
|
|
|
totalErrorCounter[channel] = 0; |
|
|
|
|
currReceiveCounter[channel] = 0; |
|
|
|
|
currLossCounter[channel] = 0; |
|
|
|
|
totalLossCounter[channel] = 0; |
|
|
|
|
runningLossPercent[channel] = 0.0f; |
|
|
|
|
for(int i = 0; i < 256; i++) { |
|
|
|
|
firstMessage[channel][i] = 1; |
|
|
|
|
} |
|
|
|
|
link->setDecodedFirstMavlinkPacket(false); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -171,6 +162,7 @@ void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link)
@@ -171,6 +162,7 @@ void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link)
|
|
|
|
|
* @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
|
|
|
|
@ -180,56 +172,67 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -180,56 +172,67 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// receiveMutex.lock();
|
|
|
|
|
mavlink_message_t message; |
|
|
|
|
mavlink_status_t status; |
|
|
|
|
|
|
|
|
|
int mavlinkChannel = link->mavlinkChannel(); |
|
|
|
|
uint8_t mavlinkChannel = link->mavlinkChannel(); |
|
|
|
|
|
|
|
|
|
static int nonmavlinkCount = 0; |
|
|
|
|
static int nonmavlinkCount = 0; |
|
|
|
|
static bool checkedUserNonMavlink = false; |
|
|
|
|
static bool warnedUserNonMavlink = false; |
|
|
|
|
static bool warnedUserNonMavlink = false; |
|
|
|
|
|
|
|
|
|
for (int position = 0; position < b.size(); position++) { |
|
|
|
|
unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status); |
|
|
|
|
|
|
|
|
|
if (decodeState == 0 && !link->decodedFirstMavlinkPacket()) |
|
|
|
|
{ |
|
|
|
|
nonmavlinkCount++; |
|
|
|
|
if (nonmavlinkCount > 1000 && !warnedUserNonMavlink) |
|
|
|
|
{ |
|
|
|
|
// 500 bytes with no mavlink message. Are we connected to a mavlink capable device?
|
|
|
|
|
if (!checkedUserNonMavlink) |
|
|
|
|
{ |
|
|
|
|
link->requestReset(); |
|
|
|
|
checkedUserNonMavlink = true; |
|
|
|
|
} |
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
warnedUserNonMavlink = true; |
|
|
|
|
// Disconnect the link since its some other device and
|
|
|
|
|
// QGC clinging on to it and feeding it data might have unintended
|
|
|
|
|
// side effects (e.g. if its a modem)
|
|
|
|
|
qDebug() << "disconnected link" << link->getName() << "as it contained no MAVLink data"; |
|
|
|
|
QMetaObject::invokeMethod(_linkMgr, "disconnectLink", Q_ARG( LinkInterface*, link ) ); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
if (decodeState == 1) |
|
|
|
|
{ |
|
|
|
|
if (mavlink_parse_char(mavlinkChannel, static_cast<uint8_t>(b[position]), &_message, &_status)) { |
|
|
|
|
// Got a valid message
|
|
|
|
|
if (!link->decodedFirstMavlinkPacket()) { |
|
|
|
|
link->setDecodedFirstMavlinkPacket(true); |
|
|
|
|
mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel); |
|
|
|
|
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; |
|
|
|
|
|
|
|
|
|
// Set all links to v2
|
|
|
|
|
setVersion(200); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
//-----------------------------------------------------------------
|
|
|
|
|
// MAVLink Status
|
|
|
|
|
uint8_t lastSeq = lastIndex[_message.sysid][_message.compid]; |
|
|
|
|
uint8_t expectedSeq = lastSeq + 1; |
|
|
|
|
// Increase receive counter
|
|
|
|
|
totalReceiveCounter[mavlinkChannel]++; |
|
|
|
|
// Determine what the next expected sequence number is, accounting for
|
|
|
|
|
// never having seen a message for this system/component pair.
|
|
|
|
|
if(firstMessage[_message.sysid][_message.compid]) { |
|
|
|
|
firstMessage[_message.sysid][_message.compid] = 0; |
|
|
|
|
lastSeq = _message.seq; |
|
|
|
|
expectedSeq = _message.seq; |
|
|
|
|
} |
|
|
|
|
// And if we didn't encounter that sequence number, record the error
|
|
|
|
|
//int foo = 0;
|
|
|
|
|
if (_message.seq != expectedSeq) |
|
|
|
|
{ |
|
|
|
|
//foo = 1;
|
|
|
|
|
int lostMessages = 0; |
|
|
|
|
//-- Account for overflow during packet loss
|
|
|
|
|
if(_message.seq < expectedSeq) { |
|
|
|
|
lostMessages = (_message.seq + 255) - expectedSeq; |
|
|
|
|
} else { |
|
|
|
|
lostMessages = _message.seq - expectedSeq; |
|
|
|
|
} |
|
|
|
|
// Log how many were lost
|
|
|
|
|
totalLossCounter[mavlinkChannel] += static_cast<uint64_t>(lostMessages); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// And update the last sequence number for this system/component pair
|
|
|
|
|
lastIndex[_message.sysid][_message.compid] = _message.seq;; |
|
|
|
|
// Calculate new loss ratio
|
|
|
|
|
uint64_t totalSent = totalReceiveCounter[mavlinkChannel] + totalLossCounter[mavlinkChannel]; |
|
|
|
|
float receiveLossPercent = static_cast<float>(static_cast<double>(totalLossCounter[mavlinkChannel]) / static_cast<double>(totalSent)); |
|
|
|
|
receiveLossPercent *= 100.0f; |
|
|
|
|
receiveLossPercent = (receiveLossPercent * 0.5f) + (runningLossPercent[mavlinkChannel] * 0.5f); |
|
|
|
|
runningLossPercent[mavlinkChannel] = receiveLossPercent; |
|
|
|
|
|
|
|
|
|
//qDebug() << foo << _message.seq << expectedSeq << lastSeq << totalLossCounter[mavlinkChannel] << totalReceiveCounter[mavlinkChannel] << totalSentCounter[mavlinkChannel] << "(" << _message.sysid << _message.compid << ")";
|
|
|
|
|
|
|
|
|
|
//-----------------------------------------------------------------
|
|
|
|
|
// Log data
|
|
|
|
|
if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) { |
|
|
|
|
uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)]; |
|
|
|
@ -237,17 +240,17 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -237,17 +240,17 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
|
|
|
|
|
// 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; |
|
|
|
|
quint64 time = static_cast<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); |
|
|
|
|
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); |
|
|
|
|
QByteArray b(reinterpret_cast<const char*>(buf), len); |
|
|
|
|
if(_tempLogFile.write(b) != len) |
|
|
|
|
{ |
|
|
|
|
// If there's an error logging data, raise an alert and stop logging.
|
|
|
|
@ -257,32 +260,32 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -257,32 +260,32 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Check for the vehicle arming going by. This is used to trigger log save.
|
|
|
|
|
if (!_vehicleWasArmed && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { |
|
|
|
|
if (!_vehicleWasArmed && _message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { |
|
|
|
|
mavlink_heartbeat_t state; |
|
|
|
|
mavlink_msg_heartbeat_decode(&message, &state); |
|
|
|
|
mavlink_msg_heartbeat_decode(&_message, &state); |
|
|
|
|
if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) { |
|
|
|
|
_vehicleWasArmed = true; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { |
|
|
|
|
if (_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { |
|
|
|
|
_startLogging(); |
|
|
|
|
mavlink_heartbeat_t heartbeat; |
|
|
|
|
mavlink_msg_heartbeat_decode(&message, &heartbeat); |
|
|
|
|
emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.autopilot, heartbeat.type); |
|
|
|
|
mavlink_msg_heartbeat_decode(&_message, &heartbeat); |
|
|
|
|
emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, heartbeat.autopilot, heartbeat.type); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY2) { |
|
|
|
|
if (_message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY2) { |
|
|
|
|
_startLogging(); |
|
|
|
|
mavlink_high_latency2_t highLatency2; |
|
|
|
|
mavlink_msg_high_latency2_decode(&message, &highLatency2); |
|
|
|
|
emit vehicleHeartbeatInfo(link, message.sysid, message.compid, highLatency2.autopilot, highLatency2.type); |
|
|
|
|
mavlink_msg_high_latency2_decode(&_message, &highLatency2); |
|
|
|
|
emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, highLatency2.autopilot, highLatency2.type); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Detect if we are talking to an old radio not supporting v2
|
|
|
|
|
mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel); |
|
|
|
|
if (message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) { |
|
|
|
|
if (_message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) { |
|
|
|
|
if ((mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) |
|
|
|
|
&& !(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) { |
|
|
|
|
|
|
|
|
@ -300,53 +303,36 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
@@ -300,53 +303,36 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
|
|
|
|
|
mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// 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
|
|
|
|
|
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
|
|
|
|
|
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]); |
|
|
|
|
// Update MAVLink status on every 32th packet
|
|
|
|
|
if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0) { |
|
|
|
|
emit mavlinkMessageStatus(_message.sysid, totalSent, totalReceiveCounter[mavlinkChannel], totalLossCounter[mavlinkChannel], receiveLossPercent); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// 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
|
|
|
|
|
emit messageReceived(link, message); |
|
|
|
|
emit messageReceived(link, _message); |
|
|
|
|
// Reset message parsing
|
|
|
|
|
memset(&_status, 0, sizeof(_status)); |
|
|
|
|
memset(&_message, 0, sizeof(_message)); |
|
|
|
|
} else if (!link->decodedFirstMavlinkPacket()) { |
|
|
|
|
// No formed message yet
|
|
|
|
|
nonmavlinkCount++; |
|
|
|
|
if (nonmavlinkCount > 1000 && !warnedUserNonMavlink) { |
|
|
|
|
// 1000 bytes with no mavlink message. Are we connected to a mavlink capable device?
|
|
|
|
|
if (!checkedUserNonMavlink) { |
|
|
|
|
link->requestReset(); |
|
|
|
|
checkedUserNonMavlink = true; |
|
|
|
|
} else { |
|
|
|
|
warnedUserNonMavlink = true; |
|
|
|
|
// Disconnect the link since it's some other device and
|
|
|
|
|
// QGC clinging on to it and feeding it data might have unintended
|
|
|
|
|
// side effects (e.g. if its a modem)
|
|
|
|
|
qDebug() << "disconnected link" << link->getName() << "as it contained no MAVLink data"; |
|
|
|
|
QMetaObject::invokeMethod(_linkMgr, "disconnectLink", Q_ARG( LinkInterface*, link ) ); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|