Commit 0f136f32 authored by pixhawk's avatar pixhawk

Added update rate calculation for incoming messages

parent 9ecf6a95
...@@ -38,7 +38,7 @@ void QGCMAVLinkInspector::refreshView() ...@@ -38,7 +38,7 @@ void QGCMAVLinkInspector::refreshView()
if (!msg) continue; if (!msg) continue;
// Update the tree view // Update the tree view
QString messageName("%1 (%2 Hz, #%3)"); QString messageName("%1 (%2 Hz, #%3)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(messagesHz.value(msg->msgid, 0)).arg(msg->msgid); messageName = messageName.arg(messageInfo[msg->msgid].name).arg(messagesHz.value(msg->msgid, 0), 2, 'f', 0).arg(msg->msgid);
if (!treeWidgetItems.contains(msg->msgid)) if (!treeWidgetItems.contains(msg->msgid))
{ {
...@@ -80,12 +80,18 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m ...@@ -80,12 +80,18 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
quint64 receiveTime = QGC::groundTimeMilliseconds(); quint64 receiveTime = QGC::groundTimeMilliseconds();
if (lastMessageUpdate.contains(message.msgid)) if (lastMessageUpdate.contains(message.msgid))
{ {
msgHz = ((float)((float)receiveTime - (float)lastMessageUpdate.value(message.msgid)))/1000.0f; msgHz = 1000.0/(double)(receiveTime - lastMessageUpdate.value(message.msgid));
qDebug() << "DIFF:" << receiveTime - lastMessageUpdate.value(message.msgid); if (isinf(msgHz) || isnan(msgHz) || msgHz < 0.0f)
messagesHz.insert(message.msgid, 0.1f*msgHz+0.9f*messagesHz.value(message.msgid, 1)); {
msgHz = 1;
}
//qDebug() << "DIFF:" << receiveTime - lastMessageUpdate.value(message.msgid);
float newHz = 0.001f*msgHz+0.999f*messagesHz.value(message.msgid, 1);
qDebug() << "HZ" << newHz;
messagesHz.insert(message.msgid, newHz);
} }
qDebug() << "MSGHZ:" << messagesHz.value(message.msgid, 1000); //qDebug() << "MSGHZ:" << messagesHz.value(message.msgid, 1000);
lastMessageUpdate.insert(message.msgid, receiveTime); lastMessageUpdate.insert(message.msgid, receiveTime);
} }
......
...@@ -27,7 +27,7 @@ public slots: ...@@ -27,7 +27,7 @@ public slots:
protected: protected:
QMap<int, quint64> lastMessageUpdate; ///< Used to switch between highlight and non-highlighting color QMap<int, quint64> lastMessageUpdate; ///< Used to switch between highlight and non-highlighting color
QMap<int, quint64> messagesHz; ///< Used to store update rate in Hz QMap<int, float> messagesHz; ///< Used to store update rate in Hz
mavlink_message_t receivedMessages[256]; ///< Available / known messages mavlink_message_t receivedMessages[256]; ///< Available / known messages
QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items
QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI
......
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