From 2a42532fc9a55ce540f9ddc1f80715e4f0df267f Mon Sep 17 00:00:00 2001 From: TobiasSimon Date: Sat, 18 Feb 2012 15:58:00 +0100 Subject: [PATCH] symptom: heartbeat Hz value was always 0 cause: check for null pointer had no effect (static memory) solution: fill mavlink messages (and thus) message type with 0xff. this patch assumes that message ID 0xff is never used positiv side effect: qgroundcontrol uses 2% less cpu on my machine (eeepc) --- src/ui/QGCMAVLinkInspector.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index 48cc8f01c..a3892d85c 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -24,7 +24,7 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *par mavlink_message_info_t msg[256] = MAVLINK_MESSAGE_INFO; memcpy(messageInfo, msg, sizeof(mavlink_message_info_t)*256); - memset(receivedMessages, 0, sizeof(mavlink_message_t)*256); + memset(receivedMessages, 0xFF, sizeof(mavlink_message_t)*256); connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t))); QStringList header; @@ -95,7 +95,7 @@ void QGCMAVLinkInspector::refreshView() { mavlink_message_t* msg = receivedMessages+i; // Ignore NULL values - if (!msg) continue; + if (msg->msgid == 0xFF) continue; // Update the tree view QString messageName("%1 (%2 Hz, #%3)"); float msgHz = (1.0f-updateHzLowpass)*messagesHz.value(msg->msgid, 0) + updateHzLowpass*((float)messageCount.value(msg->msgid, 0))/((float)updateInterval/1000.0f); -- 2.22.0