Commit af2a3970 authored by Gus Grubba's avatar Gus Grubba

Implement MAVLink Inspector (WIP)

parent f1aa7947
......@@ -42,6 +42,7 @@
<file alias="LogReplaySettings.qml">src/ui/preferences/LogReplaySettings.qml</file>
<file alias="MainRootWindow.qml">src/ui/MainRootWindow.qml</file>
<file alias="MavlinkConsolePage.qml">src/AnalyzeView/MavlinkConsolePage.qml</file>
<file alias="MAVLinkInspectorPage.qml">src/AnalyzeView/MAVLinkInspectorPage.qml</file>
<file alias="MavlinkSettings.qml">src/ui/preferences/MavlinkSettings.qml</file>
<file alias="MicrohardSettings.qml">src/Microhard/MicrohardSettings.qml</file>
<file alias="MissionSettingsEditor.qml">src/PlanView/MissionSettingsEditor.qml</file>
......
......@@ -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
......
......@@ -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
......
......@@ -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);
......
......@@ -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<int>(msgInfo->num_fields)) {
qWarning() << QStringLiteral("QGCMAVLinkMessage::update msgInfo field count mismatch msgid(%1)").arg(message->msgid);
return;
}
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) {
switch (msgInfo->fields[i].type) {
case MAVLINK_TYPE_CHAR:
if (msgInfo->fields[i].array_length > 0) {
char* str = reinterpret_cast<char*>(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<char*>(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<int8_t*>(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<int8_t*>(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<uint16_t*>(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<uint16_t*>(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<int16_t*>(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<int16_t*>(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<uint32_t*>(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<uint32_t*>(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<int32_t*>(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<int32_t*>(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<float*>(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<double>(nums[j]));
}
f->updateValue(string);
} else {
// Single value
float fv = *(reinterpret_cast<float*>(m + msgInfo->fields[i].wire_offset));
f->updateValue(QString::number(static_cast<double>(fv)));
}
break;
case MAVLINK_TYPE_DOUBLE:
if (msgInfo->fields[i].array_length > 0) {
double* nums = reinterpret_cast<double*>(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<double*>(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<uint64_t*>(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<uint64_t*>(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<int64_t*>(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<int64_t*>(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<QGCMAVLinkMessage*>(_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<QGCMAVLinkVehicle*>(_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<uint8_t>(vehicle->id()));
if(v) {
v->messages()->deleteListAndContents();
emit v->messagesChanged();
} else {
v = new QGCMAVLinkVehicle(this, static_cast<uint8_t>(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<uint8_t>(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<int, mavlink_message_t*>::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<int, QMap<int, quint64>* >::const_iterator ite = _uasLastMessageUpdate.find(message.sysid);
QMap<int, quint64>* 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<int, float>* messageHz = new QMap<int,float>;
messageHz->insert(message.msgid,0.0f);
_uasMessageHz.insertMulti(message.sysid,messageHz);
//-- Create a map for the message count
QMap<int, unsigned int>* messagesCount = new QMap<int, unsigned int>;
messagesCount->insert(message.msgid,0);
_uasMessageCount.insertMulti(message.sysid,messagesCount);
//-- Create a map for the time of reception of the message
QMap<int, quint64>* lastMessage = new QMap<int, quint64>;
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<int, QMap<int, unsigned int>* >::const_iterator iter = _uasMessageCount.find(message.sysid);
QMap<int, unsigned int> * 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<int, mavlink_message_t* >::iterator ite;
for(ite = _uasMessageStorage.begin(); ite != _uasMessageStorage.end(); ++ite) {
delete ite.value();
ite.value() = nullptr;
}
_uasMessageStorage.clear();
QMap<int, QMap<int, float>* >::iterator iteHz;
for(iteHz = _uasMessageHz.begin(); iteHz != _uasMessageHz.end(); ++iteHz) {
iteHz.value()->clear();
delete iteHz.value();
iteHz.value() = nullptr;
}
_uasMessageHz.clear();
QMap<int, QMap<int, unsigned int>*>::iterator iteCount;
for(iteCount = _uasMessageCount.begin(); iteCount != _uasMessageCount.end(); ++iteCount) {
iteCount.value()->clear();
delete iteCount.value();
iteCount.value() = nullptr;
}
_uasMessageCount.clear();
QMap<int, QMap<int, quint64>* >::iterator iteLast;
for(iteLast = _uasLastMessageUpdate.begin(); iteLast != _uasLastMessageUpdate.end(); ++iteLast) {
iteLast.value()->clear();
delete iteLast.value();
iteLast.value() = nullptr;
}
_uasLastMessageUpdate.clear();
}
......@@ -15,7 +15,90 @@
#include <QObject>
#include <QString>
#include <QDebug>
#include <QAbstractListModel>
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<int> _vehicleIDs;
QMap<int, mavlink_message_t*> _uasMessageStorage; ///< Stores the messages for every UAS
QMap<int, QMap<int, quint64>*> _uasLastMessageUpdate; ///< Stores the time of the last message for each message of each UAS
QMap<int, QMap<int, float>*> _uasMessageHz; ///< Stores the frequency of each message of each UAS
QMap<int, QMap<int, unsigned int>*> _uasMessageCount; ///< Stores the message count of each message of each UAS
QStringList _vehicleNames;
QmlObjectListModel _vehicles; //-- List of QGCMAVLinkVehicle
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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
}
}
}
}
}
}
......@@ -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<RCChannelMonitorController> (kQGCControllers, 1, 0, "RCChannelMonitorController");
qmlRegisterType<JoystickConfigController> (kQGCControllers, 1, 0, "JoystickConfigController");
qmlRegisterType<LogDownloadController> (kQGCControllers, 1, 0, "LogDownloadController");
qmlRegisterType<MAVLinkInspectorController> (kQGCControllers, 1, 0, "MAVLinkInspectorController");
qmlRegisterType<SyslinkComponentController> (kQGCControllers, 1, 0, "SyslinkComponentController");
qmlRegisterType<EditPositionDialogController> (kQGCControllers, 1, 0, "EditPositionDialogController");
......
......@@ -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)
......
......@@ -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];
}
......
......@@ -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)
......
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