Newer
Older
#include "ui_QGCMAVLinkInspector.h"
#include <QDebug>
const float QGCMAVLinkInspector::updateHzLowpass = 0.2f;
const unsigned int QGCMAVLinkInspector::updateInterval = 1000U;
QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *parent) :
QWidget(parent),
Lorenz Meier
committed
_protocol(protocol),
ui(new Ui::QGCMAVLinkInspector)
{
ui->setupUi(this);
Bryant
committed
// Make sure "All" is an option for both the system and components
ui->systemComboBox->addItem(tr("All"), 0);
ui->componentComboBox->addItem(tr("All"), 0);
Bryant
committed
// Store metadata for all MAVLink messages.
mavlink_message_info_t msg_infos[256] = MAVLINK_MESSAGE_INFO;
memcpy(messageInfo, msg_infos, sizeof(mavlink_message_info_t)*256);
// Initialize the received data for all messages to invalid (0xFF)
memset(receivedMessages, 0xFF, sizeof(mavlink_message_t)*256);
Bryant
committed
// Set up the column headers for the message listing
QStringList header;
header << tr("Name");
header << tr("Value");
header << tr("Type");
ui->treeWidget->setHeaderLabels(header);
Lorenz Meier
committed
// Set up the column headers for the rate listing
QStringList rateHeader;
rateHeader << tr("Name");
rateHeader << tr("#ID");
rateHeader << tr("Rate");
ui->rateTreeWidget->setHeaderLabels(rateHeader);
connect(ui->rateTreeWidget, SIGNAL(itemChanged(QTreeWidgetItem*,int)),
this, SLOT(rateTreeItemChanged(QTreeWidgetItem*,int)));
ui->rateTreeWidget->hide();
Bryant
committed
// Connect the UI
connect(ui->systemComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectDropDownMenuSystem(int)));
connect(ui->componentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectDropDownMenuComponent(int)));
connect(ui->clearButton, SIGNAL(clicked()), this, SLOT(clearView()));
Bryant
committed
// Connect external connections
Lorenz Meier
committed
// connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addSystem(UASInterface*)));
Bryant
committed
connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
Bryant
committed
// Attach the UI's refresh rate to a timer.
connect(&updateTimer, SIGNAL(timeout()), this, SLOT(refreshView()));
void QGCMAVLinkInspector::addSystem(UASInterface* uas)
{
ui->systemComboBox->addItem(uas->getUASName(), uas->getUASID());
}
void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid)
{
selectedSystemID = ui->systemComboBox->itemData(dropdownid).toInt();
rebuildComponentList();
Lorenz Meier
committed
if (selectedSystemID != 0 && selectedComponentID != 0) {
ui->rateTreeWidget->show();
} else {
ui->rateTreeWidget->hide();
}
}
void QGCMAVLinkInspector::selectDropDownMenuComponent(int dropdownid)
{
selectedComponentID = ui->componentComboBox->itemData(dropdownid).toInt();
Lorenz Meier
committed
if (selectedSystemID != 0 && selectedComponentID != 0) {
ui->rateTreeWidget->show();
} else {
ui->rateTreeWidget->hide();
}
}
void QGCMAVLinkInspector::rebuildComponentList()
{
ui->componentComboBox->clear();
Lorenz Meier
committed
components.clear();
Lorenz Meier
committed
ui->componentComboBox->addItem(tr("All"), 0);
}
void QGCMAVLinkInspector::addComponent(int uas, int component, const QString& name)
{
Q_UNUSED(component);
Q_UNUSED(name);
if (uas != selectedSystemID) return;
rebuildComponentList();
}
Bryant
committed
/**
* Reset the view. This entails clearing all data structures and resetting data from already-
* received messages.
*/
void QGCMAVLinkInspector::clearView()
{
Bryant
committed
memset(receivedMessages, 0xFF, sizeof(mavlink_message_t)*256);
Lorenz Meier
committed
onboardMessageInterval.clear();
Bryant
committed
lastMessageUpdate.clear();
messagesHz.clear();
treeWidgetItems.clear();
ui->treeWidget->clear();
Lorenz Meier
committed
ui->rateTreeWidget->clear();
for (int i = 0; i < 256; ++i)//mavlink_message_t msg, receivedMessages)
mavlink_message_t* msg = receivedMessages+i;
// Ignore NULL values
if (msg->msgid == 0xFF) continue;
pixhawk
committed
QString messageName("%1 (%2 Hz, #%3)");
float msgHz = (1.0f-updateHzLowpass)*messagesHz.value(msg->msgid, 0) + updateHzLowpass*((float)messageCount.value(msg->msgid, 0))/((float)updateInterval/1000.0f);
messagesHz.insert(msg->msgid, msgHz);
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msgHz, 3, 'f', 1).arg(msg->msgid);
messageCount.insert(msg->msgid, 0);
{
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);
pixhawk
committed
// Set Hz
QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid);
pixhawk
committed
message->setFirstColumnSpanned(true);
message->setData(0, Qt::DisplayRole, QVariant(messageName));
for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
{
updateField(msg->msgid, i, message->child(i));
}
}
Lorenz Meier
committed
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
if (selectedSystemID == 0 || selectedComponentID == 0)
{
return;
}
for (int i = 0; i < 256; ++i)//mavlink_message_t msg, receivedMessages)
{
const char* msgname = messageInfo[i].name;
int namelen = strnlen(msgname, 5);
if (namelen < 3) {
continue;
}
if (!strcmp(msgname, "EMPTY")) {
continue;
}
// Update the tree view
QString messageName("%1");
messageName = messageName.arg(msgname);
if (!rateTreeWidgetItems.contains(i))
{
QStringList fields;
fields << messageName;
fields << QString("%1").arg(i);
fields << "OFF / --- Hz";
QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
widget->setFlags(widget->flags() | Qt::ItemIsEditable);
rateTreeWidgetItems.insert(i, widget);
ui->rateTreeWidget->addTopLevelItem(widget);
}
// Set Hz
//QTreeWidgetItem* message = rateTreeWidgetItems.value(i);
//message->setData(0, Qt::DisplayRole, QVariant(messageName));
}
}
void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t message)
{
Q_UNUSED(link);
if (selectedSystemID != 0 && selectedSystemID != message.sysid) return;
if (selectedComponentID != 0 && selectedComponentID != message.compid) return;
// Only overwrite if system filter is set
memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));
pixhawk
committed
Lorenz Meier
committed
// Add not yet seen systems / components
if (!systems.contains(message.sysid)) {
systems.insert(message.sysid, message.sysid);
ui->systemComboBox->addItem(tr("MAV%1").arg(message.sysid), message.sysid);
}
if (!components.contains(message.compid)) {
components.insert(message.compid, message.compid);
ui->componentComboBox->addItem(tr("COMP%1").arg(message.compid), message.compid);
}
pixhawk
committed
quint64 receiveTime = QGC::groundTimeMilliseconds();
if (lastMessageUpdate.contains(message.msgid))
{
int count = messageCount.value(message.msgid, 0);
messageCount.insert(message.msgid, count+1);
pixhawk
committed
}
lastMessageUpdate.insert(message.msgid, receiveTime);
Lorenz Meier
committed
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
if (selectedSystemID == 0 || selectedComponentID == 0) {
return;
}
switch (message.msgid) {
case MAVLINK_MSG_ID_DATA_STREAM:
{
mavlink_data_stream_t stream;
mavlink_msg_data_stream_decode(&message, &stream);
onboardMessageInterval.insert(stream.stream_id, stream.message_rate);
}
break;
}
}
void QGCMAVLinkInspector::changeStreamInterval(int msgid, int interval) {
//REQUEST_DATA_STREAM
if (selectedSystemID == 0 || selectedComponentID == 0) {
return;
}
mavlink_request_data_stream_t stream;
stream.target_system = selectedSystemID;
stream.target_component = selectedComponentID;
stream.req_stream_id = msgid;
stream.req_message_rate = interval;
stream.start_stop = (interval > 0);
mavlink_message_t msg;
mavlink_msg_request_data_stream_encode(_protocol->getSystemId(), _protocol->getComponentId(), &msg, &stream);
_protocol->sendMessage(msg);
}
void QGCMAVLinkInspector::rateTreeItemChanged(QTreeWidgetItem* paramItem, int column)
{
if (paramItem && column > 0) {
int key = paramItem->data(1, Qt::DisplayRole).toInt();
QVariant value = paramItem->data(2, Qt::DisplayRole);
float interval = 1000 / value.toFloat();
qDebug() << "Stream " << key << "interval" << interval;
changeStreamInterval(key, interval);
}
}
QGCMAVLinkInspector::~QGCMAVLinkInspector()
{
delete ui;
}
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
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[fieldid].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[fieldid].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[fieldid].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[fieldid].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[fieldid].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[fieldid].array_length; ++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[fieldid].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[fieldid].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[fieldid].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");