Newer
Older
#include "QGCMAVLinkInspector.h"
#include "ui_QGCMAVLinkInspector.h"
#include <QDebug>
QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMAVLinkInspector)
{
ui->setupUi(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);
connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
QStringList header;
header << tr("Name");
header << tr("Value");
header << tr("Type");
ui->treeWidget->setHeaderLabels(header);
connect(&updateTimer, SIGNAL(timeout()), this, SLOT(refreshView()));
updateTimer.start(1000);
}
void QGCMAVLinkInspector::refreshView()
{
for (int i = 0; i < 256; ++i)//mavlink_message_t msg, receivedMessages)
mavlink_message_t* msg = receivedMessages+i;
// Ignore NULL values
if (!msg) continue;
QString messageName("%1 (#%2)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msg->msgid);
QStringList fields;
fields << messageName;
QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
widget->setFirstColumnSpanned(true);
for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
{
QTreeWidgetItem* field = new QTreeWidgetItem();
widget->addChild(field);
}
treeWidgetItems.insert(msg->msgid, widget);
QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid);
for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
{
updateField(msg->msgid, i, message->child(i));
}
}
}
void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
Q_UNUSED(link);
// Only overwrite if system filter is set
// int filterValue = ui->systemComboBox()->value().toInt();
// if (filterValue != )
memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));
}
QGCMAVLinkInspector::~QGCMAVLinkInspector()
{
delete ui;
}
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
void QGCMAVLinkInspector::updateField(int msgid, int fieldid, QTreeWidgetItem* item)
{
// Add field tree widget item
item->setData(0, Qt::DisplayRole, QVariant(messageInfo[msgid].fields[fieldid].name));
uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8;
switch (messageInfo[msgid].fields[fieldid].type)
{
case MAVLINK_TYPE_CHAR:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
char* str = (char*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
str[messageInfo[msgid].fields[fieldid].array_length-1] = '\0';
QString string(str);
item->setData(2, Qt::DisplayRole, "char");
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single char
char b = *((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, QString("char[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, b);
}
break;
case MAVLINK_TYPE_UINT8_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
uint8_t* nums = m+messageInfo[msgid].fields[fieldid].wire_offset;
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("uint8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
uint8_t u = *(m+messageInfo[msgid].fields[fieldid].wire_offset);
item->setData(2, Qt::DisplayRole, "uint8_t");
item->setData(1, Qt::DisplayRole, u);
}
break;
case MAVLINK_TYPE_INT8_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
int8_t* nums = (int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("int8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
int8_t n = *((int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "int8_t");
item->setData(1, Qt::DisplayRole, n);
}
break;
case MAVLINK_TYPE_UINT16_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
uint16_t* nums = (uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("uint16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
uint16_t n = *((uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "uint16_t");
item->setData(1, Qt::DisplayRole, n);
}
break;
case MAVLINK_TYPE_INT16_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
int16_t* nums = (int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("int16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
int16_t n = *((int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "int16_t");
item->setData(1, Qt::DisplayRole, n);
}
break;
case MAVLINK_TYPE_UINT32_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
uint32_t* nums = (uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("uint32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
float n = *((uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "uint32_t");
item->setData(1, Qt::DisplayRole, n);
}
break;
case MAVLINK_TYPE_INT32_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
int32_t* nums = (int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("int32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
int32_t n = *((int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "int32_t");
item->setData(1, Qt::DisplayRole, n);
}
break;
case MAVLINK_TYPE_FLOAT:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
float* nums = (float*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("float[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
float f = *((float*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "float");
item->setData(1, Qt::DisplayRole, f);
}
break;
case MAVLINK_TYPE_DOUBLE:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
double* nums = (double*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("double[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
double f = *((double*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "double");
item->setData(1, Qt::DisplayRole, f);
}
break;
case MAVLINK_TYPE_UINT64_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
uint64_t* nums = (uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("uint64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "uint64_t");
}
break;
case MAVLINK_TYPE_INT64_T:
if (messageInfo[msgid].fields[fieldid].array_length > 0)
{
int64_t* nums = (int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset);
// Enforce null termination
QString tmp("%1, ");
QString string;
for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j)
{
string += tmp.arg(nums[j]);
}
item->setData(2, Qt::DisplayRole, QString("int64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length));
item->setData(1, Qt::DisplayRole, string);
}
else
{
// Single value
int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset));
item->setData(2, Qt::DisplayRole, "int64_t");