Browse Source

Test message info before using it.

QGC4.4
Gus Grubba 8 years ago committed by Lorenz Meier
parent
commit
65a68c6252
  1. 8
      src/ui/MAVLinkDecoder.cc

8
src/ui/MAVLinkDecoder.cc

@ -60,10 +60,14 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag @@ -60,10 +60,14 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
{
Q_UNUSED(link);
msgDict[message.msgid] = message;
uint32_t msgid = message.msgid;
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(&message);
if(!msgInfo) {
qWarning() << "Invalid MAVLink message received. ID:" << msgid;
return;
}
msgDict[message.msgid] = message;
// Store an arrival time for this message. This value ends up being calculated later.
quint64 time = 0;

Loading…
Cancel
Save