Unverified Commit 0c6b6556 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8988 from DonLakeFlyer/InspectorMultiSystem

Mavlink Inspector: Support displaying messages from multiple systems
parents 22f4f7c5 d10e89f4
...@@ -26,7 +26,7 @@ Item { ...@@ -26,7 +26,7 @@ Item {
property alias headerComponent: headerLoader.sourceComponent property alias headerComponent: headerLoader.sourceComponent
property real availableWidth: width - pageLoader.x property real availableWidth: width - pageLoader.x
property real availableHeight: height - mainContent.y property real availableHeight: height - mainContent.y
property bool poped: false property bool popped: false
property real _margins: ScreenTools.defaultFontPixelHeight * 0.5 property real _margins: ScreenTools.defaultFontPixelHeight * 0.5
signal popout() signal popout()
...@@ -47,13 +47,13 @@ Item { ...@@ -47,13 +47,13 @@ Item {
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.rightMargin: _margins anchors.rightMargin: _margins
anchors.right: floatIcon.left anchors.right: floatIcon.visible ? floatIcon.left : parent.right
spacing: _margins spacing: _margins
visible: !ScreenTools.isShortScreen && headerLoader.sourceComponent === null visible: !ScreenTools.isShortScreen && headerLoader.sourceComponent === null
QGCLabel { QGCLabel {
id: pageNameLabel id: pageNameLabel
font.pointSize: ScreenTools.largeFontPointSize font.pointSize: ScreenTools.largeFontPointSize
visible: !poped visible: !popped
} }
QGCLabel { QGCLabel {
id: pageDescriptionLabel id: pageDescriptionLabel
...@@ -86,13 +86,10 @@ Item { ...@@ -86,13 +86,10 @@ Item {
source: "/qmlimages/FloatingWindow.svg" source: "/qmlimages/FloatingWindow.svg"
fillMode: Image.PreserveAspectFit fillMode: Image.PreserveAspectFit
color: qgcPal.text color: qgcPal.text
visible: !poped && !ScreenTools.isMobile visible: !popped && !ScreenTools.isMobile
MouseArea { MouseArea {
anchors.fill: parent anchors.fill: parent
onClicked: { onClicked: popout()
popout()
}
} }
} }
} }
...@@ -7,11 +7,6 @@ ...@@ -7,11 +7,6 @@
* *
****************************************************************************/ ****************************************************************************/
/// @file
/// @brief Setup View
/// @author Don Gagne <don@thegagnes.com>
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Window 2.2 import QtQuick.Window 2.2
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
...@@ -23,10 +18,12 @@ import QGroundControl.Controllers 1.0 ...@@ -23,10 +18,12 @@ import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
Rectangle { Rectangle {
id: setupView id: _root
color: qgcPal.window color: qgcPal.window
z: QGroundControl.zOrderTopMost z: QGroundControl.zOrderTopMost
signal popout()
ExclusiveGroup { id: setupButtonGroup } ExclusiveGroup { id: setupButtonGroup }
readonly property real _defaultTextHeight: ScreenTools.defaultFontPixelHeight readonly property real _defaultTextHeight: ScreenTools.defaultFontPixelHeight
...@@ -147,7 +144,8 @@ Rectangle { ...@@ -147,7 +144,8 @@ Rectangle {
panelLoader.source = "" panelLoader.source = ""
buttonRepeater.itemAt(_curIndex).loader.source = source buttonRepeater.itemAt(_curIndex).loader.source = source
buttonRepeater.itemAt(_curIndex).visible = false buttonRepeater.itemAt(_curIndex).visible = false
buttonRepeater.itemAt(_curIndex).loader.item.poped = true buttonRepeater.itemAt(_curIndex).loader.item.popped = true
_root.popout()
} }
} }
......
...@@ -179,6 +179,7 @@ QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message ...@@ -179,6 +179,7 @@ QGCMAVLinkMessage::QGCMAVLinkMessage(QObject *parent, mavlink_message_t* message
QGCMAVLinkMessageField* f = new QGCMAVLinkMessageField(this, msgInfo->fields[i].name, type); QGCMAVLinkMessageField* f = new QGCMAVLinkMessageField(this, msgInfo->fields[i].name, type);
_fields.append(f); _fields.append(f);
} }
update(message);
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -222,10 +223,7 @@ void ...@@ -222,10 +223,7 @@ void
QGCMAVLinkMessage::update(mavlink_message_t* message) QGCMAVLinkMessage::update(mavlink_message_t* message)
{ {
_count++; _count++;
//-- If we are not consuming this message, no need to parse it
if(!_selected && !_fieldSelected) {
return;
}
_message = *message; _message = *message;
const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message); const mavlink_message_info_t* msgInfo = mavlink_get_message_info(message);
if (!msgInfo) { if (!msgInfo) {
...@@ -454,7 +452,7 @@ QGCMAVLinkMessage::update(mavlink_message_t* message) ...@@ -454,7 +452,7 @@ QGCMAVLinkMessage::update(mavlink_message_t* message)
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCMAVLinkVehicle::QGCMAVLinkVehicle(QObject* parent, quint8 id) QGCMAVLinkSystem::QGCMAVLinkSystem(QObject* parent, quint8 id)
: QObject(parent) : QObject(parent)
, _id(id) , _id(id)
{ {
...@@ -462,14 +460,14 @@ QGCMAVLinkVehicle::QGCMAVLinkVehicle(QObject* parent, quint8 id) ...@@ -462,14 +460,14 @@ QGCMAVLinkVehicle::QGCMAVLinkVehicle(QObject* parent, quint8 id)
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCMAVLinkVehicle::~QGCMAVLinkVehicle() QGCMAVLinkSystem::~QGCMAVLinkSystem()
{ {
_messages.clearAndDeleteContents(); _messages.clearAndDeleteContents();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCMAVLinkMessage* QGCMAVLinkMessage*
QGCMAVLinkVehicle::findMessage(uint32_t id, uint8_t cid) QGCMAVLinkSystem::findMessage(uint32_t id, uint8_t cid)
{ {
for(int i = 0; i < _messages.count(); i++) { for(int i = 0; i < _messages.count(); i++) {
QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i)); QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
...@@ -484,7 +482,7 @@ QGCMAVLinkVehicle::findMessage(uint32_t id, uint8_t cid) ...@@ -484,7 +482,7 @@ QGCMAVLinkVehicle::findMessage(uint32_t id, uint8_t cid)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
int int
QGCMAVLinkVehicle::findMessage(QGCMAVLinkMessage* message) QGCMAVLinkSystem::findMessage(QGCMAVLinkMessage* message)
{ {
for(int i = 0; i < _messages.count(); i++) { for(int i = 0; i < _messages.count(); i++) {
QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i)); QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
...@@ -497,7 +495,7 @@ QGCMAVLinkVehicle::findMessage(QGCMAVLinkMessage* message) ...@@ -497,7 +495,7 @@ QGCMAVLinkVehicle::findMessage(QGCMAVLinkMessage* message)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCMAVLinkVehicle::_resetSelection() QGCMAVLinkSystem::_resetSelection()
{ {
for(int i = 0; i < _messages.count(); i++) { for(int i = 0; i < _messages.count(); i++) {
QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i)); QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(_messages.get(i));
...@@ -510,7 +508,7 @@ QGCMAVLinkVehicle::_resetSelection() ...@@ -510,7 +508,7 @@ QGCMAVLinkVehicle::_resetSelection()
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCMAVLinkVehicle::setSelected(int sel) QGCMAVLinkSystem::setSelected(int sel)
{ {
if(sel < _messages.count()) { if(sel < _messages.count()) {
_selected = sel; _selected = sel;
...@@ -537,7 +535,7 @@ messages_sort(QObject* a, QObject* b) ...@@ -537,7 +535,7 @@ messages_sort(QObject* a, QObject* b)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message) QGCMAVLinkSystem::append(QGCMAVLinkMessage* message)
{ {
//-- Save selected message //-- Save selected message
QGCMAVLinkMessage* selectedMsg = nullptr; QGCMAVLinkMessage* selectedMsg = nullptr;
...@@ -572,15 +570,15 @@ QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message) ...@@ -572,15 +570,15 @@ QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCMAVLinkVehicle::_checkCompID(QGCMAVLinkMessage* message) QGCMAVLinkSystem::_checkCompID(QGCMAVLinkMessage* message)
{ {
if(_compIDsStr.isEmpty()) { if(_compIDsStr.isEmpty()) {
_compIDsStr << tr("All"); _compIDsStr << tr("Comp All");
} }
if(!_compIDs.contains(static_cast<int>(message->cid()))) { if(!_compIDs.contains(static_cast<int>(message->cid()))) {
int cid = static_cast<int>(message->cid()); int cid = static_cast<int>(message->cid());
_compIDs.append(cid); _compIDs.append(cid);
_compIDsStr << QString::number(cid); _compIDsStr << tr("Comp %1").arg(cid);
emit compIDsChanged(); emit compIDsChanged();
} }
} }
...@@ -748,7 +746,7 @@ MAVLinkInspectorController::MAVLinkInspectorController() ...@@ -748,7 +746,7 @@ MAVLinkInspectorController::MAVLinkInspectorController()
MAVLinkInspectorController::~MAVLinkInspectorController() MAVLinkInspectorController::~MAVLinkInspectorController()
{ {
_charts.clearAndDeleteContents(); _charts.clearAndDeleteContents();
_vehicles.clearAndDeleteContents(); _systems.clearAndDeleteContents();
} }
//---------------------------------------------------------------------------------------- //----------------------------------------------------------------------------------------
...@@ -780,24 +778,24 @@ void ...@@ -780,24 +778,24 @@ void
MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle) MAVLinkInspectorController::_setActiveVehicle(Vehicle* vehicle)
{ {
if(vehicle) { if(vehicle) {
QGCMAVLinkVehicle* v = _findVehicle(static_cast<uint8_t>(vehicle->id())); QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
if(v) { if(v) {
_activeVehicle = v; _activeSystem = v;
} else { } else {
_activeVehicle = nullptr; _activeSystem = nullptr;
} }
} else { } else {
_activeVehicle = nullptr; _activeSystem = nullptr;
} }
emit activeVehiclesChanged(); emit activeSystemChanged();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCMAVLinkVehicle* QGCMAVLinkSystem*
MAVLinkInspectorController::_findVehicle(uint8_t id) MAVLinkInspectorController::_findVehicle(uint8_t id)
{ {
for(int i = 0; i < _vehicles.count(); i++) { for(int i = 0; i < _systems.count(); i++) {
QGCMAVLinkVehicle* v = qobject_cast<QGCMAVLinkVehicle*>(_vehicles.get(i)); QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
if(v) { if(v) {
if(v->id() == id) { if(v->id() == id) {
return v; return v;
...@@ -811,8 +809,8 @@ MAVLinkInspectorController::_findVehicle(uint8_t id) ...@@ -811,8 +809,8 @@ MAVLinkInspectorController::_findVehicle(uint8_t id)
void void
MAVLinkInspectorController::_refreshFrequency() MAVLinkInspectorController::_refreshFrequency()
{ {
for(int i = 0; i < _vehicles.count(); i++) { for(int i = 0; i < _systems.count(); i++) {
QGCMAVLinkVehicle* v = qobject_cast<QGCMAVLinkVehicle*>(_vehicles.get(i)); QGCMAVLinkSystem* v = qobject_cast<QGCMAVLinkSystem*>(_systems.get(i));
if(v) { if(v) {
for(int i = 0; i < v->messages()->count(); i++) { for(int i = 0; i < v->messages()->count(); i++) {
QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(v->messages()->get(i)); QGCMAVLinkMessage* m = qobject_cast<QGCMAVLinkMessage*>(v->messages()->get(i));
...@@ -828,29 +826,29 @@ MAVLinkInspectorController::_refreshFrequency() ...@@ -828,29 +826,29 @@ MAVLinkInspectorController::_refreshFrequency()
void void
MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle) MAVLinkInspectorController::_vehicleAdded(Vehicle* vehicle)
{ {
QGCMAVLinkVehicle* v = _findVehicle(static_cast<uint8_t>(vehicle->id())); QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
if(v) { if(v) {
v->messages()->clearAndDeleteContents(); v->messages()->clearAndDeleteContents();
emit v->messagesChanged(); emit v->messagesChanged();
} else { } else {
v = new QGCMAVLinkVehicle(this, static_cast<uint8_t>(vehicle->id())); v = new QGCMAVLinkSystem(this, static_cast<uint8_t>(vehicle->id()));
_vehicles.append(v); _systems.append(v);
_vehicleNames.append(tr("Vehicle %1").arg(vehicle->id())); _systemNames.append(tr("System %1").arg(vehicle->id()));
} }
emit vehiclesChanged(); emit systemsChanged();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle) MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle)
{ {
QGCMAVLinkVehicle* v = _findVehicle(static_cast<uint8_t>(vehicle->id())); QGCMAVLinkSystem* v = _findVehicle(static_cast<uint8_t>(vehicle->id()));
if(v) { if(v) {
v->deleteLater(); v->deleteLater();
_vehicles.removeOne(v); _systems.removeOne(v);
QString vs = tr("Vehicle %1").arg(vehicle->id()); QString vs = tr("System %1").arg(vehicle->id());
_vehicleNames.removeOne(vs); _systemNames.removeOne(vs);
emit vehiclesChanged(); emit systemsChanged();
} }
} }
...@@ -859,15 +857,15 @@ void ...@@ -859,15 +857,15 @@ void
MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message) MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message)
{ {
QGCMAVLinkMessage* m = nullptr; QGCMAVLinkMessage* m = nullptr;
QGCMAVLinkVehicle* v = _findVehicle(message.sysid); QGCMAVLinkSystem* v = _findVehicle(message.sysid);
if(!v) { if(!v) {
v = new QGCMAVLinkVehicle(this, message.sysid); v = new QGCMAVLinkSystem(this, message.sysid);
_vehicles.append(v); _systems.append(v);
_vehicleNames.append(tr("Vehicle %1").arg(message.sysid)); _systemNames.append(tr("System %1").arg(message.sysid));
emit vehiclesChanged(); emit systemsChanged();
if(!_activeVehicle) { if(!_activeSystem) {
_activeVehicle = v; _activeSystem = v;
emit activeVehiclesChanged(); emit activeSystemChanged();
} }
} else { } else {
m = v->findMessage(message.msgid, message.compid); m = v->findMessage(message.msgid, message.compid);
...@@ -924,3 +922,12 @@ MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l ...@@ -924,3 +922,12 @@ MAVLinkInspectorController::Range_st::Range_st(QObject* parent, const QString& l
{ {
} }
void MAVLinkInspectorController::setActiveSystem(int systemId)
{
QGCMAVLinkSystem* v = _findVehicle(systemId);
if (v != _activeSystem) {
_activeSystem = v;
emit activeSystemChanged();
}
}
...@@ -27,7 +27,7 @@ Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog) ...@@ -27,7 +27,7 @@ Q_DECLARE_LOGGING_CATEGORY(MAVLinkInspectorLog)
QT_CHARTS_USE_NAMESPACE QT_CHARTS_USE_NAMESPACE
class QGCMAVLinkMessage; class QGCMAVLinkMessage;
class QGCMAVLinkVehicle; class QGCMAVLinkSystem;
class MAVLinkChartController; class MAVLinkChartController;
class MAVLinkInspectorController; class MAVLinkInspectorController;
...@@ -137,7 +137,7 @@ private: ...@@ -137,7 +137,7 @@ private:
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
/// Vehicle MAVLink message belongs to /// Vehicle MAVLink message belongs to
class QGCMAVLinkVehicle : public QObject { class QGCMAVLinkSystem : public QObject {
Q_OBJECT Q_OBJECT
public: public:
Q_PROPERTY(quint8 id READ id CONSTANT) Q_PROPERTY(quint8 id READ id CONSTANT)
...@@ -147,8 +147,8 @@ public: ...@@ -147,8 +147,8 @@ public:
Q_PROPERTY(int selected READ selected WRITE setSelected NOTIFY selectedChanged) Q_PROPERTY(int selected READ selected WRITE setSelected NOTIFY selectedChanged)
QGCMAVLinkVehicle (QObject* parent, quint8 id); QGCMAVLinkSystem (QObject* parent, quint8 id);
~QGCMAVLinkVehicle (); ~QGCMAVLinkSystem ();
quint8 id () { return _id; } quint8 id () { return _id; }
QmlObjectListModel* messages () { return &_messages; } QmlObjectListModel* messages () { return &_messages; }
...@@ -248,22 +248,23 @@ public: ...@@ -248,22 +248,23 @@ public:
MAVLinkInspectorController(); MAVLinkInspectorController();
~MAVLinkInspectorController(); ~MAVLinkInspectorController();
Q_PROPERTY(QStringList vehicleNames READ vehicleNames NOTIFY vehiclesChanged) Q_PROPERTY(QStringList systemNames READ systemNames NOTIFY systemsChanged)
Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles NOTIFY vehiclesChanged) Q_PROPERTY(QmlObjectListModel* systems READ systems NOTIFY systemsChanged)
Q_PROPERTY(QmlObjectListModel* charts READ charts NOTIFY chartsChanged) Q_PROPERTY(QmlObjectListModel* charts READ charts NOTIFY chartsChanged)
Q_PROPERTY(QGCMAVLinkVehicle* activeVehicle READ activeVehicle NOTIFY activeVehiclesChanged) Q_PROPERTY(QGCMAVLinkSystem* activeSystem READ activeSystem NOTIFY activeSystemChanged)
Q_PROPERTY(QStringList timeScales READ timeScales NOTIFY timeScalesChanged) Q_PROPERTY(QStringList timeScales READ timeScales NOTIFY timeScalesChanged)
Q_PROPERTY(QStringList rangeList READ rangeList NOTIFY rangeListChanged) Q_PROPERTY(QStringList rangeList READ rangeList NOTIFY rangeListChanged)
Q_INVOKABLE MAVLinkChartController* createChart (); Q_INVOKABLE MAVLinkChartController* createChart ();
Q_INVOKABLE void deleteChart (MAVLinkChartController* chart); Q_INVOKABLE void deleteChart (MAVLinkChartController* chart);
Q_INVOKABLE void setActiveSystem (int systemId);
QmlObjectListModel* vehicles () { return &_vehicles; } QmlObjectListModel* systems () { return &_systems; }
QmlObjectListModel* charts () { return &_charts; } QmlObjectListModel* charts () { return &_charts; }
QGCMAVLinkVehicle* activeVehicle () { return _activeVehicle; } QGCMAVLinkSystem* activeSystem() { return _activeSystem; }
QStringList vehicleNames () { return _vehicleNames; } QStringList systemNames () { return _systemNames; }
QStringList timeScales (); QStringList timeScales ();
QStringList rangeList (); QStringList rangeList ();
class TimeScale_st : public QObject { class TimeScale_st : public QObject {
public: public:
...@@ -283,33 +284,33 @@ public: ...@@ -283,33 +284,33 @@ public:
const QList<Range_st*>& rangeSt () { return _rangeSt; } const QList<Range_st*>& rangeSt () { return _rangeSt; }
signals: signals:
void vehiclesChanged (); void systemsChanged ();
void chartsChanged (); void chartsChanged ();
void activeVehiclesChanged (); void activeSystemChanged();
void timeScalesChanged (); void timeScalesChanged ();
void rangeListChanged (); void rangeListChanged ();
private slots: private slots:
void _receiveMessage (LinkInterface* link, mavlink_message_t message); void _receiveMessage (LinkInterface* link, mavlink_message_t message);
void _vehicleAdded (Vehicle* vehicle); void _vehicleAdded (Vehicle* vehicle);
void _vehicleRemoved (Vehicle* vehicle); void _vehicleRemoved (Vehicle* vehicle);
void _setActiveVehicle (Vehicle* vehicle); void _setActiveVehicle (Vehicle* vehicle);
void _refreshFrequency (); void _refreshFrequency ();
private: private:
QGCMAVLinkVehicle* _findVehicle (uint8_t id); QGCMAVLinkSystem* _findVehicle (uint8_t id);
private: private:
int _selectedSystemID = 0; ///< Currently selected system int _selectedSystemID = 0; ///< Currently selected system
int _selectedComponentID = 0; ///< Currently selected component int _selectedComponentID = 0; ///< Currently selected component
QStringList _timeScales; QStringList _timeScales;
QStringList _rangeList; QStringList _rangeList;
QGCMAVLinkVehicle* _activeVehicle = nullptr; QGCMAVLinkSystem* _activeSystem = nullptr;
QTimer _updateFrequencyTimer; QTimer _updateFrequencyTimer;
QStringList _vehicleNames; QStringList _systemNames;
QmlObjectListModel _vehicles; ///< List of QGCMAVLinkVehicle QmlObjectListModel _systems; ///< List of QGCMAVLinkSystem
QmlObjectListModel _charts; ///< List of MAVLinkCharts QmlObjectListModel _charts; ///< List of MAVLinkCharts
QList<TimeScale_st*>_timeScaleSt; QList<TimeScale_st*>_timeScaleSt;
QList<Range_st*> _rangeSt; QList<Range_st*> _rangeSt;
......
...@@ -24,8 +24,8 @@ AnalyzePage { ...@@ -24,8 +24,8 @@ AnalyzePage {
headerComponent: headerComponent headerComponent: headerComponent
pageComponent: pageComponent pageComponent: pageComponent
property var curVehicle: controller ? controller.activeVehicle : null property var curSystem: controller ? controller.activeSystem : null
property var curMessage: curVehicle && curVehicle.messages.count ? curVehicle.messages.get(curVehicle.selected) : null property var curMessage: curSystem && curSystem.messages.count ? curSystem.messages.get(curSystem.selected) : null
property int curCompID: 0 property int curCompID: 0
property real maxButtonWidth: 0 property real maxButtonWidth: 0
...@@ -45,21 +45,39 @@ AnalyzePage { ...@@ -45,21 +45,39 @@ AnalyzePage {
} }
RowLayout { RowLayout {
Layout.alignment: Qt.AlignRight Layout.alignment: Qt.AlignRight
visible: curVehicle ? curVehicle.compIDsStr.length > 2 : false visible: curSystem ? controller.systemNames.length > 1 || curSystem.compIDsStr.length > 2 : false
QGCLabel { QGCComboBox {
text: qsTr("Component ID:") id: systemCombo
model: controller.systemNames
sizeToContents: true
visible: controller.systemNames.length > 1
onActivated: controller.setActiveSystem(controller.systems.get(index).id);
Connections {
target: controller
onActiveSystemChanged: {
for (var systemIndex=0; systemIndex<controller.systems.count; systemIndex++) {
if (controller.systems.get(systemIndex) == curSystem) {
systemCombo.currentIndex = systemIndex
curCompID = 0
cidCombo.currentIndex = 0
break
}
}
}
}
} }
QGCComboBox { QGCComboBox {
id: cidCombo id: cidCombo
model: curVehicle ? curVehicle.compIDsStr : [] model: curSystem ? curSystem.compIDsStr : []
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 10 sizeToContents: true
currentIndex: 0 visible: curSystem ? curSystem.compIDsStr.length > 2 : false
onActivated: { onActivated: {
if(curVehicle && curVehicle.compIDsStr.length > 1) { if(curSystem && curSystem.compIDsStr.length > 1) {
if(index < 1) if(index < 1)
curCompID = 0 curCompID = 0
else else
curCompID = curVehicle.compIDs[index - 1] curCompID = curSystem.compIDs[index - 1]
} }
} }
} }
...@@ -87,15 +105,15 @@ AnalyzePage { ...@@ -87,15 +105,15 @@ AnalyzePage {
anchors.right: parent.right anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelHeight * 0.25 spacing: ScreenTools.defaultFontPixelHeight * 0.25
Repeater { Repeater {
model: curVehicle ? curVehicle.messages : [] model: curSystem ? curSystem.messages : []
delegate: MAVLinkMessageButton { delegate: MAVLinkMessageButton {
text: object.name + (object.fieldSelected ? " *" : "") text: object.name + (object.fieldSelected ? " *" : "")
compID: object.cid compID: object.cid
checked: curVehicle ? (curVehicle.selected === index) : false checked: curSystem ? (curSystem.selected === index) : false
messageHz: object.messageHz messageHz: object.messageHz
visible: curCompID === 0 || curCompID === compID visible: curCompID === 0 || curCompID === compID
onClicked: { onClicked: {
curVehicle.selected = index curSystem.selected = index
} }
Layout.fillWidth: true Layout.fillWidth: true
} }
......
...@@ -522,6 +522,12 @@ ApplicationWindow { ...@@ -522,6 +522,12 @@ ApplicationWindow {
anchors.right: parent.right anchors.right: parent.right
anchors.top: toolDrawerToolbar.bottom anchors.top: toolDrawerToolbar.bottom
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
Connections {
target: toolDrawerLoader.item
ignoreUnknownSignals: true
onPopout: toolDrawer.visible = false
}
} }
} }
......
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