From 65514a8f1a4ffe011d26da1dc20aca36a45704e5 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Wed, 26 Jul 2017 23:44:46 -0400 Subject: [PATCH] Some crazy shit in UAS.cc was using an array of 256 bytes to handle received messages and mapping them to components. Well, any message ID over 255 would cause a buffer overrun. --- src/uas/UAS.cc | 13 +++++-------- src/uas/UAS.h | 5 +++-- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index bdcbe1f6b..f13cfd002 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -131,12 +131,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi _firmwarePluginManager(firmwarePluginManager) { - for (unsigned int i = 0; i<255;++i) - { - componentID[i] = -1; - componentMulti[i] = false; - } - #ifndef __mobile__ connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage); color = UASInterface::getNextColor(); @@ -210,10 +204,11 @@ void UAS::receiveMessage(mavlink_message_t message) } // Store component ID - if (componentID[message.msgid] == -1) + if (!componentID.contains(message.msgid)) { // Prefer the first component componentID[message.msgid] = message.compid; + componentMulti[message.msgid] = false; } else { @@ -225,7 +220,9 @@ void UAS::receiveMessage(mavlink_message_t message) } } - if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true; + if (componentMulti[message.msgid] == true) { + multiComponentSourceDetected = true; + } switch (message.msgid) diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 06ec98a62..421941a52 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -348,8 +348,9 @@ protected: virtual void processParamValueMsg(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue); - int componentID[256]; - bool componentMulti[256]; + QMapcomponentID; + QMapcomponentMulti; + bool connectionLost; ///< Flag indicates a timed out connection quint64 connectionLossTime; ///< Time the connection was interrupted quint64 lastVoltageWarning; ///< Time at which the last voltage warning occurred -- 2.22.0