Unverified Commit 9699bba0 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8991 from DonLakeFlyer/MavInspectorPerf

Mavlink Inspector: Performance changes
parents 26d3836f cbbadf7e
......@@ -156,7 +156,7 @@ QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message
_message = *message;
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
if (!msgInfo) {
qWarning() << QStringLiteral("QGCMAVLinkMessage NULL msgInfo msgid(%1)").arg(message->msgid);
qCWarning(MAVLinkInspectorLog) << QStringLiteral("QGCMAVLinkMessage NULL msgInfo msgid(%1)").arg(message->msgid);
return;
}
_name = QString(msgInfo->name);
......@@ -179,7 +179,6 @@ QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message
QGCMAVLinkMessageField* f = new QGCMAVLinkMessageField(this, msgInfo->fields[i].name, type);
_fields.append(f);
}
update(message);
}
//-----------------------------------------------------------------------------
......@@ -218,23 +217,41 @@ QGCMAVLinkMessage::updateFreq()
emit freqChanged();
}
void QGCMAVLinkMessage::setSelected(bool sel)
{
if (_selected != sel) {
_selected = sel;
_updateFields();
emit selectedChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCMAVLinkMessage::update(mavlink_message_t* message)
{
_count++;
_message = *message;
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
if (_selected) {
// Don't update field info unless selected to reduce perf hit of message processing
_updateFields();
}
emit countChanged();
}
void QGCMAVLinkMessage::_updateFields(void)
{
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(&_message);
if (!msgInfo) {
qWarning() << QStringLiteral("QGCMAVLinkMessage::update NULL msgInfo msgid(%1)").arg(message->msgid);
qWarning() << QStringLiteral("QGCMAVLinkMessage::update NULL msgInfo msgid(%1)").arg(_message.msgid);
return;
}
if(_fields.count() != static_cast<int>(msgInfo->num_fields)) {
qWarning() << QStringLiteral("QGCMAVLinkMessage::update msgInfo field count mismatch msgid(%1)").arg(message->msgid);
qWarning() << QStringLiteral("QGCMAVLinkMessage::update msgInfo field count mismatch msgid(%1)").arg(_message.msgid);
return;
}
uint8_t* m = reinterpret_cast<uint8_t*>(&message->payload64[0]);
uint8_t* m = reinterpret_cast<uint8_t*>(&_message.payload64[0]);
for (unsigned int i = 0; i < msgInfo->num_fields; ++i) {
QGCMAVLinkMessageField* f = qobject_cast<QGCMAVLinkMessageField*>(_fields.get(static_cast<int>(i)));
if(f) {
......@@ -448,7 +465,6 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
}
}
}
emit messageChanged();
}
//-----------------------------------------------------------------------------
......@@ -547,17 +563,12 @@ QGCMAVLinkSystem::append(QGCMAVLinkMessage* message)
}
_messages.append(message);
//-- Sort messages by id and then cid
if(_messages.count() > 0) {
if (_messages.count() > 0) {
_messages.beginReset();
std::sort(_messages.objectList()->begin(), _messages.objectList()->end(), messages_sort);
for(int i = 0; i < _messages.count(); i++) {
QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
if(m) {
emit m->indexChanged();
}
}
_messages.endReset();
_checkCompID(message);
}
emit messagesChanged();
//-- Remember selected message
if(selectedMsg) {
int idx = findMessage(selectedMsg);
......@@ -829,7 +840,6 @@ MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle)
QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
if(v) {
v->messages()->clearAndDeleteContents();
emit v->messagesChanged();
} else {
v = new QGCMAVLinkSystem(this, static_cast<uint8_t>(vehicle->id()));
_systems.append(v);
......
......@@ -90,12 +90,12 @@ private:
class QGCMAVLinkMessage : public QObject {
Q_OBJECT
public:
Q_PROPERTY(quint32 id READ id NOTIFY indexChanged)
Q_PROPERTY(quint32 cid READ cid NOTIFY indexChanged)
Q_PROPERTY(QString name READ name NOTIFY indexChanged)
Q_PROPERTY(quint32 id READ id CONSTANT)
Q_PROPERTY(quint32 cid READ cid CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(qreal messageHz READ messageHz NOTIFY freqChanged)
Q_PROPERTY(quint64 count READ count NOTIFY messageChanged)
Q_PROPERTY(QmlObjectListModel* fields READ fields NOTIFY indexChanged)
Q_PROPERTY(quint64 count READ count NOTIFY countChanged)
Q_PROPERTY(QmlObjectListModel* fields READ fields CONSTANT)
Q_PROPERTY(bool fieldSelected READ fieldSelected NOTIFY fieldSelectedChanged)
Q_PROPERTY(bool selected READ selected NOTIFY selectedChanged)
......@@ -115,24 +115,25 @@ public:
void updateFieldSelection();
void update (mavlink_message_t* message);
void updateFreq ();
void setSelected (bool sel) { _selected = sel; }
void setSelected (bool sel);
signals:
void messageChanged ();
void countChanged ();
void freqChanged ();
void indexChanged ();
void fieldSelectedChanged ();
void selectedChanged ();
private:
void _updateFields(void);
QmlObjectListModel _fields;
QString _name;
qreal _messageHz = 0.0;
uint64_t _count = 0;
uint64_t _lastCount = 0;
mavlink_message_t _message; //-- List of QGCMAVLinkMessageField
bool _fieldSelected = false;
bool _selected = false;
qreal _messageHz = 0.0;
uint64_t _count = 1;
uint64_t _lastCount = 0;
mavlink_message_t _message;
bool _fieldSelected = false;
bool _selected = false;
};
//-----------------------------------------------------------------------------
......@@ -140,11 +141,10 @@ private:
class QGCMAVLinkSystem : public QObject {
Q_OBJECT
public:
Q_PROPERTY(quint8 id READ id CONSTANT)
Q_PROPERTY(QmlObjectListModel* messages READ messages NOTIFY messagesChanged)
Q_PROPERTY(QList<int> compIDs READ compIDs NOTIFY compIDsChanged)
Q_PROPERTY(QStringList compIDsStr READ compIDsStr NOTIFY compIDsChanged)
Q_PROPERTY(quint8 id READ id CONSTANT)
Q_PROPERTY(QmlObjectListModel* messages READ messages CONSTANT)
Q_PROPERTY(QList<int> compIDs READ compIDs NOTIFY compIDsChanged)
Q_PROPERTY(QStringList compIDsStr READ compIDsStr NOTIFY compIDsChanged)
Q_PROPERTY(int selected READ selected WRITE setSelected NOTIFY selectedChanged)
QGCMAVLinkSystem (QObject* parent, quint8 id);
......@@ -162,7 +162,6 @@ public:
void append (QGCMAVLinkMessage* message);
signals:
void messagesChanged ();
void compIDsChanged ();
void selectedChanged ();
......
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