Commit f384be7e authored by Gus Grubba's avatar Gus Grubba Committed by DonLakeFlyer

Buffer overrun in UAS.cc

parent a3490362
......@@ -131,17 +131,11 @@ 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();
#endif
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)
......
......@@ -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];
QMap<int, int>componentID;
QMap<int, bool>componentMulti;
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
......
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