|
|
|
@ -1,3 +1,6 @@
@@ -1,3 +1,6 @@
|
|
|
|
|
#define MAVLINK_USE_MESSAGE_INFO |
|
|
|
|
#include <stddef.h> // Hack workaround for Mav 2.0 header problem with respect to offsetof usage |
|
|
|
|
#include "QGCMAVLink.h" |
|
|
|
|
#include "MAVLinkDecoder.h" |
|
|
|
|
|
|
|
|
|
#include <QDebug> |
|
|
|
@ -10,8 +13,6 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
@@ -10,8 +13,6 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
|
|
|
|
|
// http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
|
|
|
|
|
moveToThread(this); |
|
|
|
|
|
|
|
|
|
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); |
|
|
|
|
for (unsigned int i = 0; i<255;++i) |
|
|
|
|
{ |
|
|
|
@ -44,7 +45,6 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
@@ -44,7 +45,6 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
|
|
|
|
|
#ifdef MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE |
|
|
|
|
messageFilter.insert(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, false); |
|
|
|
|
#endif |
|
|
|
|
messageFilter.insert(MAVLINK_MSG_ID_EXTENDED_MESSAGE, false); |
|
|
|
|
messageFilter.insert(MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, false); |
|
|
|
|
|
|
|
|
|
textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG, false); |
|
|
|
@ -73,6 +73,7 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
@@ -73,6 +73,7 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
|
|
|
|
|
memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t)); |
|
|
|
|
|
|
|
|
|
uint8_t msgid = message.msgid; |
|
|
|
|
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(&message); |
|
|
|
|
|
|
|
|
|
// Store an arrival time for this message. This value ends up being calculated later.
|
|
|
|
|
quint64 time = 0; |
|
|
|
@ -91,13 +92,13 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
@@ -91,13 +92,13 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
|
|
|
|
|
// See if first value is a time value and if it is, use that as the arrival time for this data.
|
|
|
|
|
uint8_t fieldid = 0; |
|
|
|
|
uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8; |
|
|
|
|
if (QString(messageInfo[msgid].fields[fieldid].name) == QString("time_boot_ms") && messageInfo[msgid].fields[fieldid].type == MAVLINK_TYPE_UINT32_T) |
|
|
|
|
if (QString(msgInfo->fields[fieldid].name) == QString("time_boot_ms") && msgInfo->fields[fieldid].type == MAVLINK_TYPE_UINT32_T) |
|
|
|
|
{ |
|
|
|
|
time = *((quint32*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
time = *((quint32*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
} |
|
|
|
|
else if (QString(messageInfo[msgid].fields[fieldid].name).contains("usec") && messageInfo[msgid].fields[fieldid].type == MAVLINK_TYPE_UINT64_T) |
|
|
|
|
else if (QString(msgInfo->fields[fieldid].name).contains("usec") && msgInfo->fields[fieldid].type == MAVLINK_TYPE_UINT64_T) |
|
|
|
|
{ |
|
|
|
|
time = *((quint64*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
time = *((quint64*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
time = (time+500)/1000; // Scale to milliseconds, round up/down correctly
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -106,7 +107,7 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
@@ -106,7 +107,7 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
|
|
|
|
|
time = getUnixTimeFromMs(message.sysid, time); |
|
|
|
|
|
|
|
|
|
// Send out all field values for this message
|
|
|
|
|
for (unsigned int i = 0; i < messageInfo[msgid].num_fields; ++i) |
|
|
|
|
for (unsigned int i = 0; i < msgInfo->num_fields; ++i) |
|
|
|
|
{ |
|
|
|
|
emitFieldValue(&message, i, time); |
|
|
|
|
} |
|
|
|
@ -196,6 +197,7 @@ quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
@@ -196,6 +197,7 @@ quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
|
|
|
|
|
void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time) |
|
|
|
|
{ |
|
|
|
|
bool multiComponentSourceDetected = false; |
|
|
|
|
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(msg); |
|
|
|
|
|
|
|
|
|
// Store component ID
|
|
|
|
|
if (componentID[msg->msgid] == -1) |
|
|
|
@ -216,7 +218,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -216,7 +218,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
// Add field tree widget item
|
|
|
|
|
uint8_t msgid = msg->msgid; |
|
|
|
|
if (messageFilter.contains(msgid)) return; |
|
|
|
|
QString fieldName(messageInfo[msgid].fields[fieldid].name); |
|
|
|
|
QString fieldName(msgInfo->fields[fieldid].name); |
|
|
|
|
QString fieldType; |
|
|
|
|
uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8; |
|
|
|
|
QString name("%1.%2"); |
|
|
|
@ -265,7 +267,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -265,7 +267,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
// XXX this is really ugly, but we do not know a better way to do this
|
|
|
|
|
mavlink_rc_channels_raw_t raw; |
|
|
|
|
mavlink_msg_rc_channels_raw_decode(msg, &raw); |
|
|
|
|
name = name.arg(messageInfo[msgid].name).arg(fieldName); |
|
|
|
|
name = name.arg(msgInfo->name).arg(fieldName); |
|
|
|
|
name.prepend(QString("port%1_").arg(raw.port)); |
|
|
|
|
} |
|
|
|
|
else if (msgid == MAVLINK_MSG_ID_RC_CHANNELS_SCALED) |
|
|
|
@ -273,7 +275,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -273,7 +275,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
// XXX this is really ugly, but we do not know a better way to do this
|
|
|
|
|
mavlink_rc_channels_scaled_t scaled; |
|
|
|
|
mavlink_msg_rc_channels_scaled_decode(msg, &scaled); |
|
|
|
|
name = name.arg(messageInfo[msgid].name).arg(fieldName); |
|
|
|
|
name = name.arg(msgInfo->name).arg(fieldName); |
|
|
|
|
name.prepend(QString("port%1_").arg(scaled.port)); |
|
|
|
|
} |
|
|
|
|
else if (msgid == MAVLINK_MSG_ID_SERVO_OUTPUT_RAW) |
|
|
|
@ -281,12 +283,12 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -281,12 +283,12 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
// XXX this is really ugly, but we do not know a better way to do this
|
|
|
|
|
mavlink_servo_output_raw_t servo; |
|
|
|
|
mavlink_msg_servo_output_raw_decode(msg, &servo); |
|
|
|
|
name = name.arg(messageInfo[msgid].name).arg(fieldName); |
|
|
|
|
name = name.arg(msgInfo->name).arg(fieldName); |
|
|
|
|
name.prepend(QString("port%1_").arg(servo.port)); |
|
|
|
|
} |
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
name = name.arg(messageInfo[msgid].name).arg(fieldName); |
|
|
|
|
name = name.arg(msgInfo->name).arg(fieldName); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (multiComponentSourceDetected) |
|
|
|
@ -296,31 +298,31 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -296,31 +298,31 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
|
|
|
|
|
name = name.prepend(QString("M%1:").arg(msg->sysid)); |
|
|
|
|
|
|
|
|
|
switch (messageInfo[msgid].fields[fieldid].type) |
|
|
|
|
switch (msgInfo->fields[fieldid].type) |
|
|
|
|
{ |
|
|
|
|
case MAVLINK_TYPE_CHAR: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
char* str = (char*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
char* str = (char*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
// Enforce null termination
|
|
|
|
|
str[messageInfo[msgid].fields[fieldid].array_length-1] = '\0'; |
|
|
|
|
str[msgInfo->fields[fieldid].array_length-1] = '\0'; |
|
|
|
|
QString string(name + ": " + str); |
|
|
|
|
if (!textMessageFilter.contains(msgid)) emit textMessageReceived(msg->sysid, msg->compid, MAV_SEVERITY_INFO, string); |
|
|
|
|
} |
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single char
|
|
|
|
|
char b = *((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
unit = QString("char[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
char b = *((char*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
unit = QString("char[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
emit valueChanged(msg->sysid, name, unit, b, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_UINT8_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
uint8_t* nums = m+messageInfo[msgid].fields[fieldid].wire_offset; |
|
|
|
|
fieldType = QString("uint8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
uint8_t* nums = m+msgInfo->fields[fieldid].wire_offset; |
|
|
|
|
fieldType = QString("uint8_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); |
|
|
|
|
} |
|
|
|
@ -328,17 +330,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -328,17 +330,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
uint8_t u = *(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
uint8_t u = *(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = "uint8_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, u, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_INT8_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
int8_t* nums = (int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
int8_t* nums = (int8_t*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int8_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); |
|
|
|
|
} |
|
|
|
@ -346,17 +348,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -346,17 +348,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
int8_t n = *((int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
int8_t n = *((int8_t*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "int8_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, n, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_UINT16_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
uint16_t* nums = (uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("uint16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
uint16_t* nums = (uint16_t*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("uint16_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); |
|
|
|
|
} |
|
|
|
@ -364,17 +366,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -364,17 +366,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
uint16_t n = *((uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
uint16_t n = *((uint16_t*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "uint16_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, n, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_INT16_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
int16_t* nums = (int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
int16_t* nums = (int16_t*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int16_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); |
|
|
|
|
} |
|
|
|
@ -382,17 +384,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -382,17 +384,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
int16_t n = *((int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
int16_t n = *((int16_t*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "int16_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, n, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_UINT32_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
uint32_t* nums = (uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("uint32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
uint32_t* nums = (uint32_t*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("uint32_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); |
|
|
|
|
} |
|
|
|
@ -400,17 +402,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -400,17 +402,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
uint32_t n = *((uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
uint32_t n = *((uint32_t*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "uint32_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, n, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_INT32_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
int32_t* nums = (int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
int32_t* nums = (int32_t*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int32_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); |
|
|
|
|
} |
|
|
|
@ -418,17 +420,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -418,17 +420,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
int32_t n = *((int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
int32_t n = *((int32_t*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "int32_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, n, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_FLOAT: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
float* nums = (float*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("float[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
float* nums = (float*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("float[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (float)(nums[j]), time); |
|
|
|
|
} |
|
|
|
@ -436,17 +438,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -436,17 +438,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
float f = *((float*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
float f = *((float*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "float"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, f, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_DOUBLE: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
double* nums = (double*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("double[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
double* nums = (double*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("double[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); |
|
|
|
|
} |
|
|
|
@ -454,17 +456,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -454,17 +456,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
double f = *((double*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
double f = *((double*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "double"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, f, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_UINT64_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
uint64_t* nums = (uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("uint64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
uint64_t* nums = (uint64_t*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("uint64_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (quint64) nums[j], time); |
|
|
|
|
} |
|
|
|
@ -472,17 +474,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -472,17 +474,17 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
uint64_t n = *((uint64_t*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "uint64_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, (quint64) n, time); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_TYPE_INT64_T: |
|
|
|
|
if (messageInfo[msgid].fields[fieldid].array_length > 0) |
|
|
|
|
if (msgInfo->fields[fieldid].array_length > 0) |
|
|
|
|
{ |
|
|
|
|
int64_t* nums = (int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) |
|
|
|
|
int64_t* nums = (int64_t*)(m+msgInfo->fields[fieldid].wire_offset); |
|
|
|
|
fieldType = QString("int64_t[%1]").arg(msgInfo->fields[fieldid].array_length); |
|
|
|
|
for (unsigned int j = 0; j < msgInfo->fields[fieldid].array_length; ++j) |
|
|
|
|
{ |
|
|
|
|
emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, (qint64) nums[j], time); |
|
|
|
|
} |
|
|
|
@ -490,7 +492,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
@@ -490,7 +492,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
|
|
|
|
|
else |
|
|
|
|
{ |
|
|
|
|
// Single value
|
|
|
|
|
int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); |
|
|
|
|
int64_t n = *((int64_t*)(m+msgInfo->fields[fieldid].wire_offset)); |
|
|
|
|
fieldType = "int64_t"; |
|
|
|
|
emit valueChanged(msg->sysid, name, fieldType, (qint64) n, time); |
|
|
|
|
} |
|
|
|
|