diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 71ee1b18b4cbe98f814f8817c0c7280260328070..be8c92a12f0d2818ae6cbe4ee355f063c75b31f1 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -42,6 +42,7 @@ src/ui/preferences/LogReplaySettings.qml src/ui/MainRootWindow.qml src/AnalyzeView/MavlinkConsolePage.qml + src/AnalyzeView/MAVLinkInspectorPage.qml src/ui/preferences/MavlinkSettings.qml src/Microhard/MicrohardSettings.qml src/PlanView/MissionSettingsEditor.qml diff --git a/src/AnalyzeView/AnalyzePage.qml b/src/AnalyzeView/AnalyzePage.qml index e4597e8601756d7fe9ead9349d218938b189150e..ffee7ed67736adf6560e235b365be093cff5ce79 100644 --- a/src/AnalyzeView/AnalyzePage.qml +++ b/src/AnalyzeView/AnalyzePage.qml @@ -23,7 +23,7 @@ Item { property alias pageComponent: pageLoader.sourceComponent property alias pageName: pageNameLabel.text property alias pageDescription: pageDescriptionLabel.text - property real availableWidth: width - pageLoader.x + property real availableWidth: width - pageLoader.x property real availableHeight: height - pageLoader.y property real _margins: ScreenTools.defaultFontPixelHeight * 0.5 diff --git a/src/AnalyzeView/AnalyzeView.qml b/src/AnalyzeView/AnalyzeView.qml index 6741d36060fb33745079e4f190af138676bd9f08..c6cc9a3d181ddb40ecf6532ab9f490b71280a44e 100644 --- a/src/AnalyzeView/AnalyzeView.qml +++ b/src/AnalyzeView/AnalyzeView.qml @@ -26,8 +26,6 @@ Rectangle { color: qgcPal.window z: QGroundControl.zOrderTopMost - QGCPalette { id: qgcPal; colorGroupEnabled: true } - ExclusiveGroup { id: setupButtonGroup } readonly property real _defaultTextHeight: ScreenTools.defaultFontPixelHeight @@ -106,9 +104,14 @@ Rectangle { } ListElement { buttonImage: "/qmlimages/MavlinkConsoleIcon" - buttonText: qsTr("Mavlink Console") + buttonText: qsTr("MAVLink Console") pageSource: "MavlinkConsolePage.qml" } + ListElement { + buttonImage: "/qmlimages/MavlinkConsoleIcon" + buttonText: qsTr("MAVLink Inspector") + pageSource: "MAVLinkInspectorPage.qml" + } } Component.onCompleted: itemAt(0).checked = true diff --git a/src/AnalyzeView/LogDownloadController.h b/src/AnalyzeView/LogDownloadController.h index 990b0b65bc89aaf6452c911279c59df4585cc259..2a9669880f6e323d482b041f0096ad9e0054e656 100644 --- a/src/AnalyzeView/LogDownloadController.h +++ b/src/AnalyzeView/LogDownloadController.h @@ -40,7 +40,7 @@ public: ObjectRole = Qt::UserRole + 1 }; - QGCLogModel(QObject *parent = 0); + QGCLogModel(QObject *parent = nullptr); Q_PROPERTY(int count READ count NOTIFY countChanged) Q_INVOKABLE QGCLogEntry* get(int index); diff --git a/src/AnalyzeView/MAVLinkInspectorController.cc b/src/AnalyzeView/MAVLinkInspectorController.cc index e242824f4cc6186e5d89b6a2f2ed94a1f53f195c..2992ed0e627fb90bc982abc35340e4237f9ed2c1 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.cc +++ b/src/AnalyzeView/MAVLinkInspectorController.cc @@ -11,6 +11,282 @@ #include "QGCApplication.h" #include "MultiVehicleManager.h" +QGC_LOGGING_CATEGORY(MAVLinkInspectorLog, "MAVLinkInspectorLog") + +//----------------------------------------------------------------------------- +QGCMAVLinkMessageField::QGCMAVLinkMessageField(QObject* parent, QString name, QString type) + : QObject(parent) + , _type(type) + , _name(name) +{ + qCDebug(MAVLinkInspectorLog) << "Field:" << name << type; +} + +//----------------------------------------------------------------------------- +QGCMAVLinkMessage::QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message) + : QObject(parent) +{ + _message = *message; + _messageHz = QGC::groundTimeMilliseconds(); + const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message); + if (!msgInfo) { + qWarning() << QStringLiteral("QGCMAVLinkMessage NULL msgInfo msgid(%1)").arg(message->msgid); + return; + } + _name = QString(msgInfo->name); + qCDebug(MAVLinkInspectorLog) << "New Message:" << _name; + for (unsigned int i = 0; i < msgInfo->num_fields; ++i) { + QString type = QString("?"); + switch (msgInfo->fields[i].type) { + case MAVLINK_TYPE_CHAR: type = QString("char"); break; + case MAVLINK_TYPE_UINT8_T: type = QString("uint8_t"); break; + case MAVLINK_TYPE_INT8_T: type = QString("int8_t"); break; + case MAVLINK_TYPE_UINT16_T: type = QString("uint16_t"); break; + case MAVLINK_TYPE_INT16_T: type = QString("int16_t"); break; + case MAVLINK_TYPE_UINT32_T: type = QString("uint32_t"); break; + case MAVLINK_TYPE_INT32_T: type = QString("int32_t"); break; + case MAVLINK_TYPE_FLOAT: type = QString("float"); break; + case MAVLINK_TYPE_DOUBLE: type = QString("double"); break; + case MAVLINK_TYPE_UINT64_T: type = QString("uint64_t"); break; + case MAVLINK_TYPE_INT64_T: type = QString("int64_t"); break; + } + QGCMAVLinkMessageField* f = new QGCMAVLinkMessageField(this, msgInfo->fields[i].name, type); + _fields.append(f); + } +} + +//----------------------------------------------------------------------------- +void +QGCMAVLinkMessage::update(mavlink_message_t* message) +{ + _message = *message; + _count++; + _messageHz = QGC::groundTimeMilliseconds(); + const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message); + if (!msgInfo) { + qWarning() << QStringLiteral("QGCMAVLinkMessage::update NULL msgInfo msgid(%1)").arg(message->msgid); + return; + } + if(_fields.count() != static_cast(msgInfo->num_fields)) { + qWarning() << QStringLiteral("QGCMAVLinkMessage::update msgInfo field count mismatch msgid(%1)").arg(message->msgid); + return; + } + uint8_t* m = reinterpret_cast(&message->payload64[0]); + for (unsigned int i = 0; i < msgInfo->num_fields; ++i) { + QGCMAVLinkMessageField* f = qobject_cast(_fields.get(static_cast(i))); + if(f) { + switch (msgInfo->fields[i].type) { + case MAVLINK_TYPE_CHAR: + if (msgInfo->fields[i].array_length > 0) { + char* str = reinterpret_cast(m+ msgInfo->fields[i].wire_offset); + // Enforce null termination + str[msgInfo->fields[i].array_length - 1] = '\0'; + QString v(str); + f->updateValue(v); + } else { + // Single char + char b = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + QString v(b); + f->updateValue(v); + } + break; + case MAVLINK_TYPE_UINT8_T: + if (msgInfo->fields[i].array_length > 0) { + uint8_t* nums = m+msgInfo->fields[i].wire_offset; + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + uint8_t u = *(m+msgInfo->fields[i].wire_offset); + f->updateValue(QString::number(u)); + } + break; + case MAVLINK_TYPE_INT8_T: + if (msgInfo->fields[i].array_length > 0) { + int8_t* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + int8_t n = *(reinterpret_cast(m+msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(n)); + } + break; + case MAVLINK_TYPE_UINT16_T: + if (msgInfo->fields[i].array_length > 0) { + uint16_t* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + uint16_t n = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(n)); + } + break; + case MAVLINK_TYPE_INT16_T: + if (msgInfo->fields[i].array_length > 0) { + int16_t* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + int16_t n = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(n)); + } + break; + case MAVLINK_TYPE_UINT32_T: + if (msgInfo->fields[i].array_length > 0) { + uint32_t* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + uint32_t n = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(n)); + } + break; + case MAVLINK_TYPE_INT32_T: + if (msgInfo->fields[i].array_length > 0) { + int32_t* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + int32_t n = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(n)); + } + break; + case MAVLINK_TYPE_FLOAT: + if (msgInfo->fields[i].array_length > 0) { + float* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(static_cast(nums[j])); + } + f->updateValue(string); + } else { + // Single value + float fv = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(static_cast(fv))); + } + break; + case MAVLINK_TYPE_DOUBLE: + if (msgInfo->fields[i].array_length > 0) { + double* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + double d = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(d)); + } + break; + case MAVLINK_TYPE_UINT64_T: + if (msgInfo->fields[i].array_length > 0) { + uint64_t* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + uint64_t n = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(n)); + } + break; + case MAVLINK_TYPE_INT64_T: + if (msgInfo->fields[i].array_length > 0) { + int64_t* nums = reinterpret_cast(m + msgInfo->fields[i].wire_offset); + // Enforce null termination + QString tmp("%1, "); + QString string; + for (unsigned int j = 0; j < msgInfo->fields[i].array_length; ++j) { + string += tmp.arg(nums[j]); + } + f->updateValue(string); + } else { + // Single value + int64_t n = *(reinterpret_cast(m + msgInfo->fields[i].wire_offset)); + f->updateValue(QString::number(n)); + } + break; + } + } + } + emit messageChanged(); +} + +//----------------------------------------------------------------------------- +QGCMAVLinkVehicle::QGCMAVLinkVehicle(QObject* parent, quint8 id) + : QObject(parent) + , _id(id) +{ + qCDebug(MAVLinkInspectorLog) << "New Vehicle:" << id; +} + +//----------------------------------------------------------------------------- +QGCMAVLinkMessage* +QGCMAVLinkVehicle::findMessage(uint32_t id) +{ + for(int i = 0; i < _messages.count(); i++) { + QGCMAVLinkMessage* m = qobject_cast(_messages.get(i)); + if(m) { + if(m->id() == id) { + return m; + } + } + } + return nullptr; +} + +//----------------------------------------------------------------------------- +void +QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message) +{ + _messages.append(message); + emit messagesChanged(); +} + //----------------------------------------------------------------------------- MAVLinkInspectorController::MAVLinkInspectorController() { @@ -27,135 +303,77 @@ MAVLinkInspectorController::~MAVLinkInspectorController() _reset(); } +//----------------------------------------------------------------------------- +QGCMAVLinkVehicle* +MAVLinkInspectorController::_findVehicle(uint8_t id) +{ + for(int i = 0; i < _vehicles.count(); i++) { + QGCMAVLinkVehicle* v = qobject_cast(_vehicles.get(i)); + if(v) { + if(v->id() == id) { + return v; + } + } + } + return nullptr; +} + //----------------------------------------------------------------------------- void MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle) { - _vehicleIDs.append(vehicle->id()); + QGCMAVLinkVehicle* v = _findVehicle(static_cast(vehicle->id())); + if(v) { + v->messages()->deleteListAndContents(); + emit v->messagesChanged(); + } else { + v = new QGCMAVLinkVehicle(this, static_cast(vehicle->id())); + _vehicles.append(v); + _vehicleNames.append(QString(tr("Vehicle %1")).arg(vehicle->id())); + } + emit vehiclesChanged(); } //----------------------------------------------------------------------------- void MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle) { - int idx = _vehicleIDs.indexOf(vehicle->id()); - if(idx >= 0) { - _vehicleIDs.removeAt(idx); + QGCMAVLinkVehicle* v = _findVehicle(static_cast(vehicle->id())); + if(v) { + v->deleteLater(); + _vehicles.removeOne(v); + QString vs = QString(tr("Vehicle %1")).arg(vehicle->id()); + _vehicleNames.removeOne(vs); + emit vehiclesChanged(); } } //----------------------------------------------------------------------------- void -MAVLinkInspectorController::_receiveMessage(LinkInterface* link,mavlink_message_t message) +MAVLinkInspectorController::_receiveMessage(LinkInterface* link, mavlink_message_t message) { Q_UNUSED(link); - quint64 receiveTime; - if (_selectedSystemID != 0 && _selectedSystemID != message.sysid) return; - if (_selectedComponentID != 0 && _selectedComponentID != message.compid) return; - // Create dynamically an array to store the messages for each UAS - if (!_uasMessageStorage.contains(message.sysid)) { - mavlink_message_t* msg = new mavlink_message_t; - *msg = message; - _uasMessageStorage.insertMulti(message.sysid,msg); - } - bool msgFound = false; - QMap::const_iterator iteMsg = _uasMessageStorage.find(message.sysid); - mavlink_message_t* uasMessage = iteMsg.value(); - while((iteMsg != _uasMessageStorage.end()) && (iteMsg.key() == message.sysid)) { - if (iteMsg.value()->msgid == message.msgid) { - msgFound = true; - uasMessage = iteMsg.value(); - break; - } - ++iteMsg; - } - if (!msgFound) { - mavlink_message_t* msgIdMessage = new mavlink_message_t; - *msgIdMessage = message; - _uasMessageStorage.insertMulti(message.sysid,msgIdMessage); + QGCMAVLinkMessage* m = nullptr; + QGCMAVLinkVehicle* v = _findVehicle(message.sysid); + if(!v) { + v = new QGCMAVLinkVehicle(this, message.sysid); + _vehicles.append(v); + _vehicleNames.append(QString(tr("Vehicle %1")).arg(message.sysid)); + emit vehiclesChanged(); } else { - *uasMessage = message; - } - // Looking if this message has already been received once - msgFound = false; - QMap* >::const_iterator ite = _uasLastMessageUpdate.find(message.sysid); - QMap* lastMsgUpdate = ite.value(); - while((ite != _uasLastMessageUpdate.end()) && (ite.key() == message.sysid)) { - if(ite.value()->contains(message.msgid)) { - msgFound = true; - //-- Point to the found message - lastMsgUpdate = ite.value(); - break; - } - ++ite; + m = v->findMessage(message.msgid); } - receiveTime = QGC::groundTimeMilliseconds(); - //-- If the message doesn't exist, create a map for the frequency, message count and time of reception - if(!msgFound) { - //-- Create a map for the message frequency - QMap* messageHz = new QMap; - messageHz->insert(message.msgid,0.0f); - _uasMessageHz.insertMulti(message.sysid,messageHz); - //-- Create a map for the message count - QMap* messagesCount = new QMap; - messagesCount->insert(message.msgid,0); - _uasMessageCount.insertMulti(message.sysid,messagesCount); - //-- Create a map for the time of reception of the message - QMap* lastMessage = new QMap; - lastMessage->insert(message.msgid,receiveTime); - _uasLastMessageUpdate.insertMulti(message.sysid,lastMessage); - //-- Point to the created message - lastMsgUpdate = lastMessage; + if(!m) { + m = new QGCMAVLinkMessage(this, &message); + v->append(m); } else { - //-- The message has been found/created - if((lastMsgUpdate->contains(message.msgid)) && (_uasMessageCount.contains(message.sysid))) { - //-- Looking for and updating the message count - unsigned int count = 0; - QMap* >::const_iterator iter = _uasMessageCount.find(message.sysid); - QMap * uasMsgCount = iter.value(); - while((iter != _uasMessageCount.end()) && (iter.key() == message.sysid)) { - if(iter.value()->contains(message.msgid)) { - uasMsgCount = iter.value(); - count = uasMsgCount->value(message.msgid,0); - uasMsgCount->insert(message.msgid,count+1); - break; - } - ++iter; - } - } - lastMsgUpdate->insert(message.msgid,receiveTime); + m->update(&message); } + } //----------------------------------------------------------------------------- void MAVLinkInspectorController::_reset() { - QMap::iterator ite; - for(ite = _uasMessageStorage.begin(); ite != _uasMessageStorage.end(); ++ite) { - delete ite.value(); - ite.value() = nullptr; - } - _uasMessageStorage.clear(); - QMap* >::iterator iteHz; - for(iteHz = _uasMessageHz.begin(); iteHz != _uasMessageHz.end(); ++iteHz) { - iteHz.value()->clear(); - delete iteHz.value(); - iteHz.value() = nullptr; - } - _uasMessageHz.clear(); - QMap*>::iterator iteCount; - for(iteCount = _uasMessageCount.begin(); iteCount != _uasMessageCount.end(); ++iteCount) { - iteCount.value()->clear(); - delete iteCount.value(); - iteCount.value() = nullptr; - } - _uasMessageCount.clear(); - QMap* >::iterator iteLast; - for(iteLast = _uasLastMessageUpdate.begin(); iteLast != _uasLastMessageUpdate.end(); ++iteLast) { - iteLast.value()->clear(); - delete iteLast.value(); - iteLast.value() = nullptr; - } - _uasLastMessageUpdate.clear(); } diff --git a/src/AnalyzeView/MAVLinkInspectorController.h b/src/AnalyzeView/MAVLinkInspectorController.h index a9d76e9759f58d6fcbdb6a95f0107b7c613c9fa5..f73812d508ea1503c5f0344c67122313cbf49ac5 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.h +++ b/src/AnalyzeView/MAVLinkInspectorController.h @@ -15,7 +15,90 @@ #include #include #include +#include +Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog) + +//----------------------------------------------------------------------------- +class QGCMAVLinkMessageField : public QObject { + Q_OBJECT + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(QString type READ type CONSTANT) + Q_PROPERTY(QString value READ value NOTIFY valueChanged) + +public: + QGCMAVLinkMessageField(QObject* parent, QString name, QString type); + + QString name () { return _name; } + QString type () { return _type; } + QString value () { return _value; } + + void updateValue (QString newValue) { _value = newValue; emit valueChanged(); } + +signals: + void valueChanged (); + +private: + QString _type; + QString _name; + QString _value; +}; + +//----------------------------------------------------------------------------- +class QGCMAVLinkMessage : public QObject { + Q_OBJECT + Q_PROPERTY(quint32 id READ id CONSTANT) + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(quint64 messageHz READ messageHz NOTIFY messageChanged) + Q_PROPERTY(quint64 count READ count NOTIFY messageChanged) + Q_PROPERTY(QmlObjectListModel* fields READ fields CONSTANT) + +public: + QGCMAVLinkMessage(QObject* parent, mavlink_message_t* message); + + quint32 id () { return _message.msgid; } + QString name () { return _name; } + quint64 messageHz () { return _messageHz; } + quint64 count () { return _count; } + QmlObjectListModel* fields () { return &_fields; } + + void update (mavlink_message_t* message); + +signals: + void messageChanged (); + +private: + QmlObjectListModel _fields; + QString _name; + uint64_t _messageHz = 0; + uint64_t _count = 0; + mavlink_message_t _message; //-- List of QGCMAVLinkMessageField +}; + +//----------------------------------------------------------------------------- +class QGCMAVLinkVehicle : public QObject { + Q_OBJECT + Q_PROPERTY(quint8 id READ id CONSTANT) + Q_PROPERTY(QmlObjectListModel* messages READ messages NOTIFY messagesChanged) + +public: + QGCMAVLinkVehicle(QObject* parent, quint8 id); + + quint8 id () { return _id; } + QmlObjectListModel* messages () { return &_messages; } + + QGCMAVLinkMessage* findMessage (uint32_t id); + void append (QGCMAVLinkMessage* message); + +signals: + void messagesChanged (); + +private: + quint8 _id; + QmlObjectListModel _messages; //-- List of QGCMAVLinkMessage +}; + +//----------------------------------------------------------------------------- class MAVLinkInspectorController : public QObject { Q_OBJECT @@ -23,20 +106,29 @@ public: MAVLinkInspectorController(); ~MAVLinkInspectorController(); + Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged) + Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged) + + QmlObjectListModel* vehicles () { return &_vehicles; } + QStringList vehicleNames () { return _vehicleNames; } + +signals: + void vehiclesChanged (); + private slots: - void _receiveMessage (LinkInterface* link, mavlink_message_t message); - void _vehicleAdded (Vehicle* vehicle); - void _vehicleRemoved (Vehicle* vehicle); + void _receiveMessage (LinkInterface* link, mavlink_message_t message); + void _vehicleAdded (Vehicle* vehicle); + void _vehicleRemoved (Vehicle* vehicle); private: - void _reset (); + void _reset (); + + QGCMAVLinkVehicle* _findVehicle (uint8_t id); private: int _selectedSystemID = 0; ///< Currently selected system int _selectedComponentID = 0; ///< Currently selected component - QList _vehicleIDs; - QMap _uasMessageStorage; ///< Stores the messages for every UAS - QMap*> _uasLastMessageUpdate; ///< Stores the time of the last message for each message of each UAS - QMap*> _uasMessageHz; ///< Stores the frequency of each message of each UAS - QMap*> _uasMessageCount; ///< Stores the message count of each message of each UAS + + QStringList _vehicleNames; + QmlObjectListModel _vehicles; //-- List of QGCMAVLinkVehicle }; diff --git a/src/AnalyzeView/MAVLinkInspectorPage.qml b/src/AnalyzeView/MAVLinkInspectorPage.qml new file mode 100644 index 0000000000000000000000000000000000000000..05820ae5f2f638e5364af3848cfd084f48573000 --- /dev/null +++ b/src/AnalyzeView/MAVLinkInspectorPage.qml @@ -0,0 +1,162 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +import QtQuick 2.11 +import QtQuick.Controls 2.4 +import QtQuick.Layouts 1.11 +import QtQuick.Dialogs 1.3 + +import QGroundControl 1.0 +import QGroundControl.Palette 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.Controllers 1.0 +import QGroundControl.ScreenTools 1.0 + +Item { + anchors.fill: parent + anchors.margins: ScreenTools.defaultFontPixelWidth + + readonly property real _butttonWidth: ScreenTools.defaultFontPixelWidth * 30 + + property int curVehicleIndex: 0 + property var curVehicle: controller.vehicles.count > 0 ? controller.vehicles.get(curVehicleIndex) : null + property int curMessageIndex: 0 + property var curMessage: curVehicle && curVehicle.messages.count ? curVehicle.messages.get(curMessageIndex) : null + + MAVLinkInspectorController { + id: controller + } + + DeadMouseArea { + anchors.fill: parent + } + + //-- Header + ColumnLayout { + id: header + width: parent.width + spacing: ScreenTools.defaultFontPixelHeight + QGCLabel { + text: qsTr("Analyze real time MAVLink messages.") + } + RowLayout { + Layout.fillWidth: true + spacing: ScreenTools.defaultFontPixelWidth + QGCLabel { + text: qsTr("Vehicle:") + } + QGCComboBox { + id: vehicleSelector + model: controller.vehicleNames + enabled: controller.vehicles.count > 0 + onActivated: curVehicleIndex = index + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 16 + } + } + Item { + height: ScreenTools.defaultFontPixelHeight + width: 1 + } + } + //-- Messages + QGCFlickable { + id: buttonGrid + anchors.top: header.bottom + anchors.bottom: parent.bottom + anchors.left: parent.left + width: ScreenTools.defaultFontPixelWidth * 32 + contentWidth: buttonCol.width + contentHeight: buttonCol.height + ColumnLayout { + id: buttonCol + spacing: ScreenTools.defaultFontPixelHeight * 0.25 + Repeater { + model: curVehicle ? curVehicle.messages : [] + delegate: QGCButton { + text: object.name + onClicked: curMessageIndex = index + Layout.minimumWidth: _butttonWidth + } + } + } + } + //-- Message Data + QGCFlickable { + id: messageGrid + anchors.top: header.bottom + anchors.bottom: parent.bottom + anchors.left: buttonGrid.right + anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 2 + anchors.right: parent.right + contentWidth: messageCol.width + contentHeight: messageCol.height + Column { + id: messageCol + spacing: ScreenTools.defaultFontPixelHeight + GridLayout { + columns: 2 + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25 + QGCLabel { + text: qsTr("Message:") + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 20 + } + QGCLabel { + color: qgcPal.buttonHighlight + text: curMessage ? curMessage.name : "" + } + QGCLabel { + text: qsTr("Count:") + } + QGCLabel { + text: curMessage ? curMessage.count : "" + } + QGCLabel { + text: qsTr("Frequency:") + } + QGCLabel { + text: curMessage ? curMessage.messageHz + 'Hz' : "" + } + } + GridLayout { + columns: 3 + columnSpacing: ScreenTools.defaultFontPixelWidth + rowSpacing: ScreenTools.defaultFontPixelHeight * 0.25 + Repeater { + model: curMessage ? curMessage.fields : [] + delegate: QGCLabel { + Layout.row: index + Layout.column: 0 + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 20 + text: object.name + } + } + Repeater { + model: curMessage ? curMessage.fields : [] + delegate: QGCLabel { + Layout.row: index + Layout.column: 1 + Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 30 + Layout.maximumWidth: ScreenTools.defaultFontPixelWidth * 30 + wrapMode: Text.WordWrap + text: object.value + } + } + Repeater { + model: curMessage ? curMessage.fields : [] + delegate: QGCLabel { + Layout.row: index + Layout.column: 2 + text: object.type + } + } + } + } + } +} diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 0bae32550e6efd0fe9b39e1da35ae15a5557aa7d..6d0b9b81c81395993bde7027b0a57c65a7227cac 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -77,6 +77,7 @@ #include "VideoSurface.h" #include "VideoReceiver.h" #include "LogDownloadController.h" +#include "MAVLinkInspectorController.h" #include "ValuesWidgetController.h" #include "AppMessages.h" #include "SimulatedPosition.h" @@ -452,6 +453,7 @@ void QGCApplication::_initCommon() qmlRegisterType (kQGCControllers, 1, 0, "RCChannelMonitorController"); qmlRegisterType (kQGCControllers, 1, 0, "JoystickConfigController"); qmlRegisterType (kQGCControllers, 1, 0, "LogDownloadController"); + qmlRegisterType (kQGCControllers, 1, 0, "MAVLinkInspectorController"); qmlRegisterType (kQGCControllers, 1, 0, "SyslinkComponentController"); qmlRegisterType (kQGCControllers, 1, 0, "EditPositionDialogController"); diff --git a/src/QmlControls/QGCFlickable.qml b/src/QmlControls/QGCFlickable.qml index c86fd39b1a5dd787c2f614b8b284c3e37c49b62c..3fbb86904c441fc7cce9430d0de390412487b21d 100644 --- a/src/QmlControls/QGCFlickable.qml +++ b/src/QmlControls/QGCFlickable.qml @@ -10,8 +10,6 @@ Flickable { property color indicatorColor: qgcPal.text - QGCPalette { id: qgcPal; colorGroupEnabled: enabled } - Component.onCompleted: { var indicatorComponent = Qt.createComponent("QGCFlickableVerticalIndicator.qml") indicatorComponent.createObject(root) diff --git a/src/QmlControls/QmlObjectListModel.cc b/src/QmlControls/QmlObjectListModel.cc index 64764a3651c9bf379a5ff71645f6d748246250b6..b2c62d4198d98b542cb0112f535462f4c90b9815 100644 --- a/src/QmlControls/QmlObjectListModel.cc +++ b/src/QmlControls/QmlObjectListModel.cc @@ -119,7 +119,7 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p QObject* QmlObjectListModel::operator[](int index) { if (index < 0 || index >= _objectList.count()) { - return NULL; + return nullptr; } return _objectList[index]; } @@ -127,7 +127,7 @@ QObject* QmlObjectListModel::operator[](int index) const QObject* QmlObjectListModel::operator[](int index) const { if (index < 0 || index >= _objectList.count()) { - return NULL; + return nullptr; } return _objectList[index]; } diff --git a/src/QmlControls/QmlObjectListModel.h b/src/QmlControls/QmlObjectListModel.h index d7db98d753d8caa2624066f4425ff4b85669b5c3..c87519ea3255985294db39b4c98c7ae1677117e1 100644 --- a/src/QmlControls/QmlObjectListModel.h +++ b/src/QmlControls/QmlObjectListModel.h @@ -18,8 +18,8 @@ class QmlObjectListModel : public QAbstractListModel Q_OBJECT public: - QmlObjectListModel(QObject* parent = NULL); - ~QmlObjectListModel(); + QmlObjectListModel(QObject* parent = nullptr); + ~QmlObjectListModel() override; Q_PROPERTY(int count READ count NOTIFY countChanged)