Unverified Commit b87cc26a authored by Don Gagne's avatar Don Gagne Committed by GitHub

Param load from file: Support unknown params, diff ui (#9112)

parent 7221d50c
......@@ -4,6 +4,8 @@ Note: This file only contains high level features or important fixes.
## 4.1 - Daily build
* Load Parameters From File: Support loading parameters which don't currently existing on the vehicle.
* Load Parameters From File: Add dialog which shows diff of file and vehicle params. Selective param upload from file.
* Video Streaming: New camera control supports capturing individual images from the stream
* Fly: Press and hold on arm button will change it to Force Arm. Click again to force arm.
* VTOL: General setting for transition distance which affects Plan takeoff, landing pattern creation
......
......@@ -116,6 +116,7 @@
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/MultiRotorMotorDisplay.qml">src/QmlControls/MultiRotorMotorDisplay.qml</file>
<file alias="QGroundControl/Controls/OfflineMapButton.qml">src/QmlControls/OfflineMapButton.qml</file>
<file alias="QGroundControl/Controls/ParameterDiffDialog.qml">src/QmlControls/ParameterDiffDialog.qml</file>
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="QGroundControl/Controls/PIDTuning.qml">src/QmlControls/PIDTuning.qml</file>
......
......@@ -7,12 +7,7 @@
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef Fact_H
#define Fact_H
#pragma once
#include "FactMetaData.h"
......@@ -215,5 +210,3 @@ protected:
FactValueSliderListModel* _valueSliderModel;
bool _ignoreQGCRebootRequired;
};
#endif
......@@ -36,9 +36,8 @@ const qreal FactMetaData::UnitConsts_s::inchesToCentimeters = 2.54;
const qreal FactMetaData::UnitConsts_s::ouncesToGrams = 28.3495;
const qreal FactMetaData::UnitConsts_s::poundsToGrams = 453.592;
static const char* kDefaultCategory = QT_TRANSLATE_NOOP("FactMetaData", "Other");
static const char* kDefaultGroup = QT_TRANSLATE_NOOP("FactMetaData", "Misc");
const char* FactMetaData::kDefaultCategory = QT_TRANSLATE_NOOP("FactMetaData", "Other");
const char* FactMetaData::kDefaultGroup = QT_TRANSLATE_NOOP("FactMetaData", "Misc");
const char* FactMetaData::qgcFileType = "FactMetaData";
const char* FactMetaData::_jsonMetaDataDefinesName = "QGC.MetaData.Defines";
......
......@@ -194,6 +194,8 @@ public:
static const int kDefaultDecimalPlaces = 3; ///< Default value for decimal places if not specified/known
static const int kUnknownDecimalPlaces = -1; ///< Number of decimal places to specify is not known
static const char* kDefaultCategory;
static const char* kDefaultGroup;
static ValueType_t stringToType(const QString& typeString, bool& unknownType);
static QString typeToString(ValueType_t type);
......
This diff is collapsed.
......@@ -27,10 +27,14 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
class ParameterEditorController;
class ParameterManager : public QObject
{
Q_OBJECT
friend class ParameterEditorController;
public:
/// @param uas Uas which this set of facts is associated with
ParameterManager(Vehicle* vehicle);
......@@ -50,6 +54,8 @@ public:
/// @return Location of parameter cache file
static QString parameterCacheFile(int vehicleId, int componentId);
void mavlinkMessageReceived(mavlink_message_t message);
QList<int> componentIds(void);
/// Re-request the full set of parameters from the autopilot
......@@ -78,70 +84,55 @@ public:
/// @param name: Parameter name
Fact* getParameter(int componentId, const QString& paramName);
int getComponentId(const QString& category);
QString getComponentCategory(int componentId);
const QMap<QString, QMap<QString, QStringList> >& getComponentCategoryMap(int componentId);
/// Returns error messages from loading
QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(QTextStream& stream);
/// Returns the version number for the parameter set, -1 if not known
int parameterSetVersion(void) { return _parameterSetMajorVersion; }
bool pendingWrites(void);
Vehicle* vehicle(void) { return _vehicle; }
static MAV_PARAM_TYPE factTypeToMavType(FactMetaData::ValueType_t factType);
static FactMetaData::ValueType_t mavTypeToFactType(MAV_PARAM_TYPE mavType);
signals:
void parametersReadyChanged (bool parametersReady);
void missingParametersChanged (bool missingParameters);
void loadProgressChanged (float value);
void pendingWritesChanged (bool pendingWrites);
void factAdded (int componentId, Fact* fact);
protected:
Vehicle* _vehicle;
MAVLinkProtocol* _mavlink;
void _parameterUpdate (int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
void _valueUpdated (const QVariant& value);
void _waitingParamTimeout (void);
void _tryCacheLookup (void);
void _initialRequestTimeout (void);
private slots:
void _factRawValueUpdated (const QVariant& rawValue);
private:
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
void _handleParamValue (int componentId, QString parameterName, int parameterCount, int parameterIndex, MAV_PARAM_TYPE mavParamType, QVariant parameterValue);
void _factRawValueUpdateWorker (int componentId, const QString& name, FactMetaData::ValueType_t valueType, const QVariant& rawValue);
void _waitingParamTimeout (void);
void _tryCacheLookup (void);
void _initialRequestTimeout (void);
int _actualComponentId (int componentId);
void _setupComponentCategoryMap (int componentId);
void _setupDefaultComponentCategoryMap (void);
void _readParameterRaw (int componentId, const QString& paramName, int paramIndex);
void _writeParameterRaw (int componentId, const QString& paramName, const QVariant& value);
void _sendParamSetToVehicle (int componentId, const QString& paramName, FactMetaData::ValueType_t valueType, const QVariant& value);
void _writeLocalParamCache (int vehicleId, int componentId);
void _tryCacheHashLoad (int vehicleId, int componentId, QVariant hash_value);
void _loadMetaData (void);
void _clearMetaData (void);
void _addMetaDataToDefaultComponent (void);
QString _remapParamNameToVersion (const QString& paramName);
void _loadOfflineEditingParams (void);
QString _logVehiclePrefix (int componentId);
void _setLoadProgress (double loadProgress);
bool _fillIndexBatchQueue (bool waitingParamTimeout);
void _updateProgressBar (void);
void _checkInitialLoadComplete (void);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
void _checkInitialLoadComplete(void);
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
/// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant;
Vehicle* _vehicle;
MAVLinkProtocol* _mavlink;
// List of category map of component parameters
typedef QMap<QString, QMap<QString, QStringList>> ComponentCategoryMapType; //<Key: category, Value: Map< Key: group, Value: parameter names list >>
QMap<int, ComponentCategoryMapType> _componentCategoryMaps;
QHash<QString, int> _componentCategoryHash;
QMap<int /* comp id */, QMap<QString /* parameter name */, Fact*>> _mapCompId2FactMap;
double _loadProgress; ///< Parameter load progess, [0.0,1.0]
bool _parametersReady; ///< true: parameter load complete
......@@ -151,8 +142,6 @@ private:
bool _saveRequired; ///< true: _saveToEEPROM should be called
bool _metaDataAddedToFacts; ///< true: FactMetaData has been adde to the default component facts
bool _logReplay; ///< true: running with log replay link
QString _versionParam; ///< Parameter which contains parameter set version
int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known
typedef QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;
......
......@@ -98,7 +98,6 @@ public:
void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
QString getVersionParam (void) override { return QStringLiteral("SYSID_SW_MREV"); }
QString _internalParameterMetaDataFile (Vehicle* vehicle) override;
FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override;
void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
......
......@@ -242,9 +242,6 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
QString group = _groupFromParameterName(name);
QString category = xml.attributes().value("user").toString();
if (category.isEmpty()) {
category = QStringLiteral("Advanced");
}
QString shortDescription = xml.attributes().value("humanName").toString();
QString longDescription = xml.attributes().value("documentation").toString();
......@@ -266,7 +263,9 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
}
qCDebug(APMParameterMetaDataVerboseLog) << "inserting metadata for field" << name;
rawMetaData->name = name;
rawMetaData->category = category;
if (!category.isEmpty()) {
rawMetaData->category = category;
}
rawMetaData->group = group;
rawMetaData->shortDescription = shortDescription;
rawMetaData->longDescription = longDescription;
......@@ -448,7 +447,9 @@ FactMetaData* APMParameterMetaData::getMetaDataForFact(const QString& name, MAV_
}
metaData->setName(rawMetaData->name);
metaData->setCategory(rawMetaData->category);
if (!rawMetaData->category.isEmpty()) {
metaData->setCategory(rawMetaData->category);
}
metaData->setGroup(rawMetaData->group);
metaData->setVehicleRebootRequired(rawMetaData->rebootRequired);
......
......@@ -209,9 +209,6 @@ public:
/// false: Do not send first item to vehicle, sequence numbers must be adjusted
virtual bool sendHomePositionToVehicle(void);
/// Returns the parameter which is used to identify the version number of parameter set
virtual QString getVersionParam(void) { return QString(); }
/// Returns the parameter set version info pulled from inside the meta data file. -1 if not found.
/// Note: The implementation for this must not vary by vehicle type.
/// Important: Only CompInfoParam code should use this method
......
......@@ -56,7 +56,6 @@ public:
void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
QString getVersionParam (void) override { return QString("SYS_PARAM_VER"); }
FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override;
QString _internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override;
......
......@@ -7,9 +7,7 @@
*
****************************************************************************/
#ifndef PX4ParameterMetaData_H
#define PX4ParameterMetaData_H
#pragma once
#include <QObject>
#include <QMap>
......@@ -60,5 +58,3 @@ private:
bool _parameterMetaDataLoaded = false; ///< true: parameter meta data already loaded
FactMetaData::NameToMetaDataMap_t _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData
};
#endif
/****************************************************************************
*
* (c) 2009-2020 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.12
import QtQuick.Layouts 1.2
import QtQuick.Controls 2.5
import QtQuick.Dialogs 1.3
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Controllers 1.0
QGCPopupDialog {
title: qsTr("Load Parameters")
buttons: StandardButton.Cancel | (paramController.diffList.count ? StandardButton.Ok : 0)
property var paramController
function accept() {
hideDialog()
paramController.sendDiff();
}
Component.onDestruction: paramController.clearDiff();
ColumnLayout {
spacing: ScreenTools.defaultDialogControlSpacing
QGCLabel {
Layout.preferredWidth: mainGrid.visible ? mainGrid.width : ScreenTools.defaultFontPixelWidth * 40
wrapMode: Text.WordWrap
text: paramController.diffList.count ?
qsTr("The following parameters from the loaded file differ from what is currently set on the Vehicle. Click 'Ok' to update them on the Vehicle.") :
qsTr("There are no differences between the file loaded and the current settings on the Vehicle.")
}
GridLayout {
id: mainGrid
rows: paramController.diffList.count + 1
columns: paramController.diffMultipleComponents ? 5 : 4
flow: GridLayout.TopToBottom
visible: paramController.diffList.count
QGCCheckBox {
checked: true
onClicked: {
for (var i=0; i<paramController.diffList.count; i++) {
paramController.diffList.get(i).load = checked
}
}
}
Repeater {
model: paramController.diffList
QGCCheckBox {
checked: object.load
onClicked: object.load = checked
}
}
Repeater {
model: paramController.diffMultipleComponents ? 1 : 0
QGCLabel { text: qsTr("Comp ID") }
}
Repeater {
model: paramController.diffMultipleComponents ? paramController.diffList : 0
QGCLabel { text: object.componentId }
}
QGCLabel { text: qsTr("Name") }
Repeater {
model: paramController.diffList
QGCLabel { text: object.name }
}
QGCLabel { text: qsTr("File") }
Repeater {
model: paramController.diffList
QGCLabel { text: object.fileValue + " " + object.units }
}
QGCLabel { text: qsTr("Vehicle") }
Repeater {
model: paramController.diffList
QGCLabel { text: object.noVehicleValue ? qsTr("N/A") : object.vehicleValue + " " + object.units }
}
}
}
}
......@@ -26,15 +26,15 @@ Item {
property Fact _editorDialogFact: Fact { }
property int _rowHeight: ScreenTools.defaultFontPixelHeight * 2
property int _rowWidth: 10 // Dynamic adjusted at runtime
property bool _searchFilter: searchText.text.trim() != "" ///< true: showing results of search
property bool _searchFilter: searchText.text.trim() != "" || controller.showModifiedOnly ///< true: showing results of search
property var _searchResults ///< List of parameter names from search results
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _showRCToParam: _activeVehicle.px4Firmware
property var _appSettings: QGroundControl.settingsManager.appSettings
property var _controller: controller
ParameterEditorController {
id: controller
onShowErrorMessage: mainWindow.showMessageDialog(qsTr("Parameter Load Errors"), errorMsg)
id: controller
}
ExclusiveGroup { id: sectionGroup }
......@@ -82,12 +82,11 @@ Item {
}
QGCCheckBox {
text: qsTr("Show modified only")
checked: controller.showModifiedOnly
text: qsTr("Show modified only")
anchors.verticalCenter: parent.verticalCenter
onClicked: {
controller.showModifiedOnly = !controller.showModifiedOnly
}
checked: controller.showModifiedOnly
onClicked: controller.showModifiedOnly = checked
visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
}
} // Row - Header
......@@ -155,7 +154,7 @@ Item {
pixelAligned: true
contentHeight: groupedViewCategoryColumn.height
flickableDirection: Flickable.VerticalFlick
visible: !_searchFilter && !controller.showModifiedOnly
visible: !_searchFilter
ColumnLayout {
id: groupedViewCategoryColumn
......@@ -170,41 +169,36 @@ Item {
Layout.fillWidth: true
spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25)
readonly property string category: modelData
SectionHeader {
id: categoryHeader
anchors.left: parent.left
anchors.right: parent.right
text: category
checked: controller.currentCategory === text
text: object.name
checked: object == controller.currentCategory
exclusiveGroup: sectionGroup
onCheckedChanged: {
if (checked) {
controller.currentCategory = category
controller.currentGroup = controller.getGroupsForCategory(category)[0]
controller.currentCategory = object
}
}
}
Repeater {
model: categoryHeader.checked ? controller.getGroupsForCategory(category) : 0
model: categoryHeader.checked ? object.groups : 0
QGCButton {
width: ScreenTools.defaultFontPixelWidth * 25
text: groupName
text: object.name
height: _rowHeight
checked: controller.currentGroup === text
checked: object == controller.currentGroup
autoExclusive: true
readonly property string groupName: modelData
onClicked: {
if (!checked) _rowWidth = 10
checked = true
controller.currentCategory = category
controller.currentGroup = groupName
controller.currentGroup = object
}
}
}
......@@ -217,7 +211,7 @@ Item {
QGCListView {
id: editorListView
anchors.leftMargin: ScreenTools.defaultFontPixelWidth
anchors.left: (_searchFilter || controller.showModifiedOnly) ? parent.left : groupScroll.right
anchors.left: _searchFilter ? parent.left : groupScroll.right
anchors.right: parent.right
anchors.top: header.bottom
anchors.bottom: parent.bottom
......@@ -295,8 +289,10 @@ Item {
}
onAcceptedForLoad: {
controller.loadFromFile(file)
close()
if (controller.buildDiffFromFile(file)) {
mainWindow.showPopupDialogFromComponent(parameterDiffDialog)
}
}
}
......@@ -355,4 +351,12 @@ Item {
}
}
}
Component {
id: parameterDiffDialog
ParameterDiffDialog {
paramController: _controller
}
}
}
......@@ -7,12 +7,7 @@
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef PARAMETEREDITORCONTROLLER_H
#define PARAMETEREDITORCONTROLLER_H
#pragma once
#include <QObject>
#include <QList>
......@@ -23,6 +18,69 @@
#include "QmlObjectListModel.h"
#include "ParameterManager.h"
class ParameterEditorGroup : public QObject
{
Q_OBJECT
public:
ParameterEditorGroup(QObject* parent) : QObject(parent) { }
Q_PROPERTY(QString name MEMBER name CONSTANT)
Q_PROPERTY(QmlObjectListModel* facts READ getFacts CONSTANT)
QmlObjectListModel* getFacts(void) { return &facts; }
int componentId;
QString name;
QmlObjectListModel facts;
};
class ParameterEditorCategory : public QObject
{
Q_OBJECT
public:
ParameterEditorCategory(QObject* parent) : QObject(parent) { }
Q_PROPERTY(QString name MEMBER name CONSTANT)
Q_PROPERTY(QmlObjectListModel* groups READ getGroups CONSTANT)
QmlObjectListModel* getGroups(void) { return &groups; }
QString name;
QmlObjectListModel groups;
QMap<QString, ParameterEditorGroup*> mapGroupName2Group;
};
class ParameterEditorDiff : public QObject
{
Q_OBJECT
public:
ParameterEditorDiff(QObject* parent) : QObject(parent) { }
Q_PROPERTY(int componentId MEMBER componentId CONSTANT)
Q_PROPERTY(QString name MEMBER name CONSTANT)
Q_PROPERTY(QString fileValue MEMBER fileValue CONSTANT)
Q_PROPERTY(QString vehicleValue MEMBER vehicleValue CONSTANT)
Q_PROPERTY(bool noVehicleValue MEMBER noVehicleValue CONSTANT)
Q_PROPERTY(QString units MEMBER units CONSTANT)
Q_PROPERTY(bool load MEMBER load NOTIFY loadChanged)
int componentId;
QString name;
FactMetaData::ValueType_t valueType;
QString fileValue;
QVariant fileValueVar;
QString vehicleValue;
bool noVehicleValue = false;
QString units;
bool load = true;
signals:
void loadChanged(bool load);
};
class ParameterEditorController : public FactPanelController
{
Q_OBJECT
......@@ -31,46 +89,67 @@ public:
ParameterEditorController(void);
~ParameterEditorController();
Q_PROPERTY(QString searchText MEMBER _searchText NOTIFY searchTextChanged)
Q_PROPERTY(QString currentCategory MEMBER _currentCategory NOTIFY currentCategoryChanged)
Q_PROPERTY(QString currentGroup MEMBER _currentGroup NOTIFY currentGroupChanged)
Q_PROPERTY(QmlObjectListModel* parameters MEMBER _parameters CONSTANT)
Q_PROPERTY(QStringList categories MEMBER _categories CONSTANT)
Q_PROPERTY(bool showModifiedOnly MEMBER _showModifiedOnly NOTIFY showModifiedOnlyChanged)
Q_PROPERTY(QString searchText MEMBER _searchText NOTIFY searchTextChanged)
Q_PROPERTY(QmlObjectListModel* categories READ categories CONSTANT)
Q_PROPERTY(QObject* currentCategory READ currentCategory WRITE setCurrentCategory NOTIFY currentCategoryChanged)
Q_PROPERTY(QObject* currentGroup READ currentGroup WRITE setCurrentGroup NOTIFY currentGroupChanged)
Q_PROPERTY(QmlObjectListModel* parameters MEMBER _parameters NOTIFY parametersChanged)
Q_PROPERTY(bool showModifiedOnly MEMBER _showModifiedOnly NOTIFY showModifiedOnlyChanged)
Q_INVOKABLE QStringList getGroupsForCategory(const QString& category);
Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true);
// These property are related to the diff associated with a load from file
Q_PROPERTY(bool diffOtherVehicle MEMBER _diffOtherVehicle NOTIFY diffOtherVehicleChanged)
Q_PROPERTY(bool diffMultipleComponents MEMBER _diffMultipleComponents NOTIFY diffMultipleComponentsChanged)
Q_PROPERTY(QmlObjectListModel* diffList READ diffList CONSTANT)
Q_INVOKABLE void saveToFile(const QString& filename);
Q_INVOKABLE void loadFromFile(const QString& filename);
Q_INVOKABLE void refresh(void);
Q_INVOKABLE void resetAllToDefaults(void);
Q_INVOKABLE void resetAllToVehicleConfiguration(void);
Q_INVOKABLE void setRCToParam(const QString& paramName);
Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true);
QList<QObject*> model(void);
Q_INVOKABLE void saveToFile (const QString& filename);
Q_INVOKABLE bool buildDiffFromFile (const QString& filename);
Q_INVOKABLE void clearDiff (void);
Q_INVOKABLE void sendDiff (void);
Q_INVOKABLE void refresh (void);
Q_INVOKABLE void resetAllToDefaults (void);
Q_INVOKABLE void resetAllToVehicleConfiguration (void);
QObject* currentCategory (void) { return _currentCategory; }
QObject* currentGroup (void) { return _currentGroup; }
QmlObjectListModel* categories (void) { return &_categories; }
QmlObjectListModel* diffList (void) { return &_diffList; }
void setCurrentCategory (QObject* currentCategory);
void setCurrentGroup (QObject* currentGroup);
signals:
void searchTextChanged(QString searchText);
void currentCategoryChanged(QString category);
void currentGroupChanged(QString group);
void showErrorMessage(const QString& errorMsg);
void showModifiedOnlyChanged();
void searchTextChanged (QString searchText);
void currentCategoryChanged (void);
void currentGroupChanged (void);
void showModifiedOnlyChanged (void);
void diffOtherVehicleChanged (bool diffOtherVehicle);
void diffMultipleComponentsChanged (bool diffMultipleComponents);
void parametersChanged (void);
private slots:
void _updateParameters(void);
void _currentCategoryChanged(void);
void _currentGroupChanged (void);
void _searchTextChanged (void);
void _buildLists (void);
void _buildListsForComponent(int compId);
void _factAdded (int compId, Fact* fact);
private:
bool _shouldShow(Fact *fact);
private:
QStringList _categories;
QString _searchText;
QString _currentCategory;
QString _currentGroup;
QmlObjectListModel* _parameters;
ParameterManager* _parameterMgr;
bool _showModifiedOnly;
ParameterManager* _parameterMgr = nullptr;
QString _searchText;
ParameterEditorCategory* _currentCategory = nullptr;
ParameterEditorGroup* _currentGroup = nullptr;
bool _showModifiedOnly = false;
bool _diffOtherVehicle = false;
bool _diffMultipleComponents = false;
QmlObjectListModel _categories;
QmlObjectListModel _diffList;
QmlObjectListModel _searchParameters;
QmlObjectListModel* _parameters = nullptr;
QMap<QString, ParameterEditorCategory*> _mapCategoryName2Category;
};
#endif
......@@ -12,6 +12,7 @@ TabButton {
id: control
font.pointSize: ScreenTools.defaultFontPointSize
font.family: ScreenTools.normalFontFamily
icon.color: _showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText
property bool _showHighlight: (pressed | hovered | checked)
......@@ -22,7 +23,6 @@ TabButton {
mirrored: control.mirrored
display: control.display
icon: control.icon
text: control.text
font: control.font
color: _showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText
}
......
......@@ -43,6 +43,7 @@ MissionItemStatus 1.0 MissionItemStatus.qml
ModeSwitchDisplay 1.0 ModeSwitchDisplay.qml
MultiRotorMotorDisplay 1.0 MultiRotorMotorDisplay.qml
OfflineMapButton 1.0 OfflineMapButton.qml
ParameterDiffDialog 1.0 ParameterDiffDialog.qml
ParameterEditor 1.0 ParameterEditor.qml
ParameterEditorDialog 1.0 ParameterEditorDialog.qml
PIDTuning 1.0 PIDTuning.qml
......
......@@ -89,9 +89,14 @@ FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaDa
{
FactMetaData* factMetaData = nullptr;
if (_opaqueParameterMetaData) {
factMetaData = vehicle->firmwarePlugin()->_getMetaDataForFact(_opaqueParameterMetaData, name, type, vehicle->vehicleType());
} else {