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,6 +4,8 @@ Note: This file only contains high level features or important fixes.
## 4.1 - Daily build ## 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 * 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. * 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 * VTOL: General setting for transition distance which affects Plan takeoff, landing pattern creation
......
...@@ -116,6 +116,7 @@ ...@@ -116,6 +116,7 @@
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file> <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/MultiRotorMotorDisplay.qml">src/QmlControls/MultiRotorMotorDisplay.qml</file>
<file alias="QGroundControl/Controls/OfflineMapButton.qml">src/QmlControls/OfflineMapButton.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/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file> <file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="QGroundControl/Controls/PIDTuning.qml">src/QmlControls/PIDTuning.qml</file> <file alias="QGroundControl/Controls/PIDTuning.qml">src/QmlControls/PIDTuning.qml</file>
......
...@@ -7,12 +7,7 @@ ...@@ -7,12 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#pragma once
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef Fact_H
#define Fact_H
#include "FactMetaData.h" #include "FactMetaData.h"
...@@ -215,5 +210,3 @@ protected: ...@@ -215,5 +210,3 @@ protected:
FactValueSliderListModel* _valueSliderModel; FactValueSliderListModel* _valueSliderModel;
bool _ignoreQGCRebootRequired; bool _ignoreQGCRebootRequired;
}; };
#endif
...@@ -36,9 +36,8 @@ const qreal FactMetaData::UnitConsts_s::inchesToCentimeters = 2.54; ...@@ -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::ouncesToGrams = 28.3495;
const qreal FactMetaData::UnitConsts_s::poundsToGrams = 453.592; const qreal FactMetaData::UnitConsts_s::poundsToGrams = 453.592;
const char* FactMetaData::kDefaultCategory = QT_TRANSLATE_NOOP("FactMetaData", "Other");
static const char* kDefaultCategory = QT_TRANSLATE_NOOP("FactMetaData", "Other"); const char* FactMetaData::kDefaultGroup = QT_TRANSLATE_NOOP("FactMetaData", "Misc");
static const char* kDefaultGroup = QT_TRANSLATE_NOOP("FactMetaData", "Misc");
const char* FactMetaData::qgcFileType = "FactMetaData"; const char* FactMetaData::qgcFileType = "FactMetaData";
const char* FactMetaData::_jsonMetaDataDefinesName = "QGC.MetaData.Defines"; const char* FactMetaData::_jsonMetaDataDefinesName = "QGC.MetaData.Defines";
......
...@@ -194,6 +194,8 @@ public: ...@@ -194,6 +194,8 @@ public:
static const int kDefaultDecimalPlaces = 3; ///< Default value for decimal places if not specified/known 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 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 ValueType_t stringToType(const QString& typeString, bool& unknownType);
static QString typeToString(ValueType_t type); static QString typeToString(ValueType_t type);
......
This diff is collapsed.
...@@ -27,10 +27,14 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log) ...@@ -27,10 +27,14 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
class ParameterEditorController;
class ParameterManager : public QObject class ParameterManager : public QObject
{ {
Q_OBJECT Q_OBJECT
friend class ParameterEditorController;
public: public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
ParameterManager(Vehicle* vehicle); ParameterManager(Vehicle* vehicle);
...@@ -50,6 +54,8 @@ public: ...@@ -50,6 +54,8 @@ public:
/// @return Location of parameter cache file /// @return Location of parameter cache file
static QString parameterCacheFile(int vehicleId, int componentId); static QString parameterCacheFile(int vehicleId, int componentId);
void mavlinkMessageReceived(mavlink_message_t message);
QList<int> componentIds(void); QList<int> componentIds(void);
/// Re-request the full set of parameters from the autopilot /// Re-request the full set of parameters from the autopilot
...@@ -78,70 +84,55 @@ public: ...@@ -78,70 +84,55 @@ public:
/// @param name: Parameter name /// @param name: Parameter name
Fact* getParameter(int componentId, const QString& paramName); 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 /// Returns error messages from loading
QString readParametersFromStream(QTextStream& stream); QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(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); bool pendingWrites(void);
Vehicle* vehicle(void) { return _vehicle; } Vehicle* vehicle(void) { return _vehicle; }
static MAV_PARAM_TYPE factTypeToMavType(FactMetaData::ValueType_t factType);
static FactMetaData::ValueType_t mavTypeToFactType(MAV_PARAM_TYPE mavType);
signals: signals:
void parametersReadyChanged (bool parametersReady); void parametersReadyChanged (bool parametersReady);
void missingParametersChanged (bool missingParameters); void missingParametersChanged (bool missingParameters);
void loadProgressChanged (float value); void loadProgressChanged (float value);
void pendingWritesChanged (bool pendingWrites); void pendingWritesChanged (bool pendingWrites);
void factAdded (int componentId, Fact* fact);
protected: private slots:
Vehicle* _vehicle; void _factRawValueUpdated (const QVariant& rawValue);
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: 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); int _actualComponentId (int componentId);
void _setupComponentCategoryMap (int componentId);
void _setupDefaultComponentCategoryMap (void);
void _readParameterRaw (int componentId, const QString& paramName, int paramIndex); 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 _writeLocalParamCache (int vehicleId, int componentId);
void _tryCacheHashLoad (int vehicleId, int componentId, QVariant hash_value); void _tryCacheHashLoad (int vehicleId, int componentId, QVariant hash_value);
void _loadMetaData (void); void _loadMetaData (void);
void _clearMetaData (void); void _clearMetaData (void);
void _addMetaDataToDefaultComponent (void);
QString _remapParamNameToVersion (const QString& paramName); QString _remapParamNameToVersion (const QString& paramName);
void _loadOfflineEditingParams (void); void _loadOfflineEditingParams (void);
QString _logVehiclePrefix (int componentId); QString _logVehiclePrefix (int componentId);
void _setLoadProgress (double loadProgress); void _setLoadProgress (double loadProgress);
bool _fillIndexBatchQueue (bool waitingParamTimeout); bool _fillIndexBatchQueue (bool waitingParamTimeout);
void _updateProgressBar (void); void _updateProgressBar (void);
void _checkInitialLoadComplete (void);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
void _checkInitialLoadComplete(void);
/// First mapping is by component id Vehicle* _vehicle;
/// Second mapping is parameter name, to Fact* in QVariant MAVLinkProtocol* _mavlink;
QMap<int, QVariantMap> _mapParameterName2Variant;
// List of category map of component parameters QMap<int /* comp id */, QMap<QString /* parameter name */, Fact*>> _mapCompId2FactMap;
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;
double _loadProgress; ///< Parameter load progess, [0.0,1.0] double _loadProgress; ///< Parameter load progess, [0.0,1.0]
bool _parametersReady; ///< true: parameter load complete bool _parametersReady; ///< true: parameter load complete
...@@ -151,8 +142,6 @@ private: ...@@ -151,8 +142,6 @@ private:
bool _saveRequired; ///< true: _saveToEEPROM should be called bool _saveRequired; ///< true: _saveToEEPROM should be called
bool _metaDataAddedToFacts; ///< true: FactMetaData has been adde to the default component facts bool _metaDataAddedToFacts; ///< true: FactMetaData has been adde to the default component facts
bool _logReplay; ///< true: running with log replay link 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 QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal; typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;
......
...@@ -98,7 +98,6 @@ public: ...@@ -98,7 +98,6 @@ public:
void initializeVehicle (Vehicle* vehicle) override; void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override; bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override; QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
QString getVersionParam (void) override { return QStringLiteral("SYSID_SW_MREV"); }
QString _internalParameterMetaDataFile (Vehicle* vehicle) override; QString _internalParameterMetaDataFile (Vehicle* vehicle) override;
FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) 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); } 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 ...@@ -242,9 +242,6 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
QString group = _groupFromParameterName(name); QString group = _groupFromParameterName(name);
QString category = xml.attributes().value("user").toString(); QString category = xml.attributes().value("user").toString();
if (category.isEmpty()) {
category = QStringLiteral("Advanced");
}
QString shortDescription = xml.attributes().value("humanName").toString(); QString shortDescription = xml.attributes().value("humanName").toString();
QString longDescription = xml.attributes().value("documentation").toString(); QString longDescription = xml.attributes().value("documentation").toString();
...@@ -266,7 +263,9 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData ...@@ -266,7 +263,9 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
} }
qCDebug(APMParameterMetaDataVerboseLog) << "inserting metadata for field" << name; qCDebug(APMParameterMetaDataVerboseLog) << "inserting metadata for field" << name;
rawMetaData->name = name; rawMetaData->name = name;
rawMetaData->category = category; if (!category.isEmpty()) {
rawMetaData->category = category;
}
rawMetaData->group = group; rawMetaData->group = group;
rawMetaData->shortDescription = shortDescription; rawMetaData->shortDescription = shortDescription;
rawMetaData->longDescription = longDescription; rawMetaData->longDescription = longDescription;
...@@ -448,7 +447,9 @@ FactMetaData* APMParameterMetaData::getMetaDataForFact(const QString& name, MAV_ ...@@ -448,7 +447,9 @@ FactMetaData* APMParameterMetaData::getMetaDataForFact(const QString& name, MAV_
} }
metaData->setName(rawMetaData->name); metaData->setName(rawMetaData->name);
metaData->setCategory(rawMetaData->category); if (!rawMetaData->category.isEmpty()) {
metaData->setCategory(rawMetaData->category);
}
metaData->setGroup(rawMetaData->group); metaData->setGroup(rawMetaData->group);
metaData->setVehicleRebootRequired(rawMetaData->rebootRequired); metaData->setVehicleRebootRequired(rawMetaData->rebootRequired);
......
...@@ -209,9 +209,6 @@ public: ...@@ -209,9 +209,6 @@ public:
/// false: Do not send first item to vehicle, sequence numbers must be adjusted /// false: Do not send first item to vehicle, sequence numbers must be adjusted
virtual bool sendHomePositionToVehicle(void); 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. /// 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. /// Note: The implementation for this must not vary by vehicle type.
/// Important: Only CompInfoParam code should use this method /// Important: Only CompInfoParam code should use this method
......
...@@ -56,7 +56,6 @@ public: ...@@ -56,7 +56,6 @@ public:
void initializeVehicle (Vehicle* vehicle) override; void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override; bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const 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; 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"); } QString _internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override; void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override;
......
...@@ -7,9 +7,7 @@ ...@@ -7,9 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#pragma once
#ifndef PX4ParameterMetaData_H
#define PX4ParameterMetaData_H
#include <QObject> #include <QObject>
#include <QMap> #include <QMap>
...@@ -60,5 +58,3 @@ private: ...@@ -60,5 +58,3 @@ private:
bool _parameterMetaDataLoaded = false; ///< true: parameter meta data already loaded bool _parameterMetaDataLoaded = false; ///< true: parameter meta data already loaded
FactMetaData::NameToMetaDataMap_t _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData 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 { ...@@ -26,15 +26,15 @@ Item {
property Fact _editorDialogFact: Fact { } property Fact _editorDialogFact: Fact { }
property int _rowHeight: ScreenTools.defaultFontPixelHeight * 2 property int _rowHeight: ScreenTools.defaultFontPixelHeight * 2
property int _rowWidth: 10 // Dynamic adjusted at runtime 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 _searchResults ///< List of parameter names from search results
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _showRCToParam: _activeVehicle.px4Firmware property bool _showRCToParam: _activeVehicle.px4Firmware
property var _appSettings: QGroundControl.settingsManager.appSettings property var _appSettings: QGroundControl.settingsManager.appSettings
property var _controller: controller
ParameterEditorController { ParameterEditorController {
id: controller id: controller
onShowErrorMessage: mainWindow.showMessageDialog(qsTr("Parameter Load Errors"), errorMsg)
} }
ExclusiveGroup { id: sectionGroup } ExclusiveGroup { id: sectionGroup }
...@@ -82,12 +82,11 @@ Item { ...@@ -82,12 +82,11 @@ Item {
} }
QGCCheckBox { QGCCheckBox {
text: qsTr("Show modified only") text: qsTr("Show modified only")
checked: controller.showModifiedOnly
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
onClicked: { checked: controller.showModifiedOnly
controller.showModifiedOnly = !controller.showModifiedOnly onClicked: controller.showModifiedOnly = checked
} visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
} }
} // Row - Header } // Row - Header
...@@ -155,7 +154,7 @@ Item { ...@@ -155,7 +154,7 @@ Item {
pixelAligned: true pixelAligned: true
contentHeight: groupedViewCategoryColumn.height contentHeight: groupedViewCategoryColumn.height
flickableDirection: Flickable.VerticalFlick flickableDirection: Flickable.VerticalFlick
visible: !_searchFilter && !controller.showModifiedOnly visible: !_searchFilter
ColumnLayout { ColumnLayout {
id: groupedViewCategoryColumn id: groupedViewCategoryColumn
...@@ -170,41 +169,36 @@ Item { ...@@ -170,41 +169,36 @@ Item {
Layout.fillWidth: true Layout.fillWidth: true
spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25) spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25)
readonly property string category: modelData
SectionHeader { SectionHeader {
id: categoryHeader id: categoryHeader
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
text: category text: object.name
checked: controller.currentCategory === text checked: object == controller.currentCategory
exclusiveGroup: sectionGroup exclusiveGroup: sectionGroup
onCheckedChanged: { onCheckedChanged: {
if (checked) { if (checked) {
controller.currentCategory = category controller.currentCategory = object
controller.currentGroup = controller.getGroupsForCategory(category)[0]
} }
} }
} }
Repeater { Repeater {
model: categoryHeader.checked ? controller.getGroupsForCategory(category) : 0 model: categoryHeader.checked ? object.groups : 0
QGCButton { QGCButton {
width: ScreenTools.defaultFontPixelWidth * 25 width: ScreenTools.defaultFontPixelWidth * 25
text: groupName text: object.name
height: _rowHeight height: _rowHeight
checked: controller.currentGroup === text checked: object == controller.currentGroup
autoExclusive: true autoExclusive: true
readonly property string groupName: modelData
onClicked: { onClicked: {
if (!checked) _rowWidth = 10 if (!checked) _rowWidth = 10
checked = true checked = true
controller.currentCategory = category controller.currentGroup = object
controller.currentGroup = groupName
} }
} }
} }
...@@ -217,7 +211,7 @@ Item { ...@@ -217,7 +211,7 @@ Item {
QGCListView { QGCListView {
id: editorListView id: editorListView
anchors.leftMargin: ScreenTools.defaultFontPixelWidth 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.right: parent.right
anchors.top: header.bottom anchors.top: header.bottom
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
...@@ -295,8 +289,10 @@ Item { ...@@ -295,8 +289,10 @@ Item {
} }
onAcceptedForLoad: { onAcceptedForLoad: {
controller.loadFromFile(file)
close() close()
if (controller.buildDiffFromFile(file)) {
mainWindow.showPopupDialogFromComponent(parameterDiffDialog)
}
} }
} }
...@@ -355,4 +351,12 @@ Item { ...@@ -355,4 +351,12 @@ Item {
} }
} }
} }
Component {
id: parameterDiffDialog
ParameterDiffDialog {
paramController: _controller
}
}
} }
...@@ -7,12 +7,7 @@ ...@@ -7,12 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#pragma once
/// @file
/// @author Don Gagne <don@thegagnes.com>
#ifndef PARAMETEREDITORCONTROLLER_H
#define PARAMETEREDITORCONTROLLER_H
#include <QObject> #include <QObject>
#include <QList> #include <QList>
...@@ -23,6 +18,69 @@ ...@@ -23,6 +18,69 @@
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include "ParameterManager.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 class ParameterEditorController : public FactPanelController
{ {
Q_OBJECT Q_OBJECT
...@@ -31,46 +89,67 @@ public: ...@@ -31,46 +89,67 @@ public:
ParameterEditorController(void); ParameterEditorController(void);
~ParameterEditorController(); ~ParameterEditorController();
Q_PROPERTY(QString searchText MEMBER _searchText NOTIFY searchTextChanged) Q_PROPERTY(QString searchText MEMBER _searchText NOTIFY searchTextChanged)
Q_PROPERTY(QString currentCategory MEMBER _currentCategory NOTIFY currentCategoryChanged) Q_PROPERTY(QmlObjectListModel* categories READ categories CONSTANT)
Q_PROPERTY(QString currentGroup MEMBER _currentGroup NOTIFY currentGroupChanged) Q_PROPERTY(QObject* currentCategory READ currentCategory WRITE setCurrentCategory NOTIFY currentCategoryChanged)
Q_PROPERTY(QmlObjectListModel* parameters MEMBER _parameters CONSTANT) Q_PROPERTY(QObject* currentGroup READ currentGroup WRITE setCurrentGroup NOTIFY currentGroupChanged)
Q_PROPERTY(QStringList categories MEMBER _categories CONSTANT) Q_PROPERTY(QmlObjectListModel* parameters MEMBER _parameters NOTIFY parametersChanged)
Q_PROPERTY(bool showModifiedOnly MEMBER _showModifiedOnly NOTIFY showModifiedOnlyChanged) Q_PROPERTY(bool showModifiedOnly MEMBER _showModifiedOnly NOTIFY showModifiedOnlyChanged)
Q_INVOKABLE QStringList getGroupsForCategory(const QString& category); // These property are related to the diff associated with a load from file
Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true); 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 QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true);
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);
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: signals:
void searchTextChanged(QString searchText); void searchTextChanged (QString searchText);
void currentCategoryChanged(QString category); void currentCategoryChanged (void);
void currentGroupChanged(QString group); void currentGroupChanged (void);
void showErrorMessage(const QString& errorMsg); void showModifiedOnlyChanged (void);
void showModifiedOnlyChanged(); void diffOtherVehicleChanged (bool diffOtherVehicle);
void diffMultipleComponentsChanged (bool diffMultipleComponents);
void parametersChanged (void);
private slots: 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: private:
bool _shouldShow(Fact *fact); bool _shouldShow(Fact *fact);
private: private:
QStringList _categories; ParameterManager* _parameterMgr = nullptr;
QString _searchText; QString _searchText;
QString _currentCategory; ParameterEditorCategory* _currentCategory = nullptr;
QString _currentGroup; ParameterEditorGroup* _currentGroup = nullptr;
QmlObjectListModel* _parameters; bool _showModifiedOnly = false;
ParameterManager* _parameterMgr; bool _diffOtherVehicle = false;
bool _showModifiedOnly; bool _diffMultipleComponents = false;
QmlObjectListModel _categories;
QmlObjectListModel _diffList;
QmlObjectListModel _searchParameters;
QmlObjectListModel* _parameters = nullptr;
QMap<QString, ParameterEditorCategory*> _mapCategoryName2Category;
}; };
#endif
...@@ -12,6 +12,7 @@ TabButton { ...@@ -12,6 +12,7 @@ TabButton {
id: control id: control
font.pointSize: ScreenTools.defaultFontPointSize font.pointSize: ScreenTools.defaultFontPointSize
font.family: ScreenTools.normalFontFamily font.family: ScreenTools.normalFontFamily
icon.color: _showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText
property bool _showHighlight: (pressed | hovered | checked) property bool _showHighlight: (pressed | hovered | checked)
...@@ -22,7 +23,6 @@ TabButton { ...@@ -22,7 +23,6 @@ TabButton {
mirrored: control.mirrored mirrored: control.mirrored
display: control.display display: control.display
icon: control.icon icon: control.icon
text: control.text
font: control.font font: control.font
color: _showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText color: _showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText
} }
......
...@@ -43,6 +43,7 @@ MissionItemStatus 1.0 MissionItemStatus.qml ...@@ -43,6 +43,7 @@ MissionItemStatus 1.0 MissionItemStatus.qml
ModeSwitchDisplay 1.0 ModeSwitchDisplay.qml ModeSwitchDisplay 1.0 ModeSwitchDisplay.qml
MultiRotorMotorDisplay 1.0 MultiRotorMotorDisplay.qml MultiRotorMotorDisplay 1.0 MultiRotorMotorDisplay.qml
OfflineMapButton 1.0 OfflineMapButton.qml OfflineMapButton 1.0 OfflineMapButton.qml
ParameterDiffDialog 1.0 ParameterDiffDialog.qml
ParameterEditor 1.0 ParameterEditor.qml ParameterEditor 1.0 ParameterEditor.qml
ParameterEditorDialog 1.0 ParameterEditorDialog.qml ParameterEditorDialog 1.0 ParameterEditorDialog.qml
PIDTuning 1.0 PIDTuning.qml PIDTuning 1.0 PIDTuning.qml
......
...@@ -89,9 +89,14 @@ FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaDa ...@@ -89,9 +89,14 @@ FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaDa
{ {
FactMetaData* factMetaData = nullptr; FactMetaData* factMetaData = nullptr;
if (_opaqueParameterMetaData) { if (_noJsonMetadata) {
factMetaData = vehicle->firmwarePlugin()->_getMetaDataForFact(_opaqueParameterMetaData, name, type, vehicle->vehicleType()); QObject* opaqueMetaData = _getOpaqueParameterMetaData();
} else { if (opaqueMetaData) {
factMetaData = vehicle->firmwarePlugin()->_getMetaDataForFact(opaqueMetaData, name, type, vehicle->vehicleType());
}
}
if (!factMetaData) {
if (_nameToMetaDataMap.contains(name)) { if (_nameToMetaDataMap.contains(name)) {
factMetaData = _nameToMetaDataMap[name]; factMetaData = _nameToMetaDataMap[name];
} else { } else {
...@@ -122,22 +127,31 @@ FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaDa ...@@ -122,22 +127,31 @@ FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaDa
if (!factMetaData) { if (!factMetaData) {
factMetaData = new FactMetaData(type, this); factMetaData = new FactMetaData(type, this);
int i = name.indexOf("_");
if (i > 0) {
factMetaData->setGroup(name.left(i));
}
if (compId != MAV_COMP_ID_AUTOPILOT1) {
factMetaData->setCategory(tr("Component %1").arg(compId));
}
} }
_nameToMetaDataMap[name] = factMetaData; _nameToMetaDataMap[name] = factMetaData;
} }
} }
return factMetaData; return factMetaData;
} }
bool CompInfoParam::_isParameterVolatile(const QString& name) bool CompInfoParam::_isParameterVolatile(const QString& name)
{ {
if (_opaqueParameterMetaData) { if (_noJsonMetadata) {
return vehicle->firmwarePlugin()->_isParameterVolatile(_opaqueParameterMetaData, name, vehicle->vehicleType()); QObject* opaqueMetaData = _getOpaqueParameterMetaData();
} else { if (opaqueMetaData) {
return _nameToMetaDataMap.contains(name) ? _nameToMetaDataMap[name]->volatileValue() : false; return vehicle->firmwarePlugin()->_isParameterVolatile(opaqueMetaData, name, vehicle->vehicleType());
}
} }
return _nameToMetaDataMap.contains(name) ? _nameToMetaDataMap[name]->volatileValue() : false;
} }
FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType) FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType)
...@@ -148,13 +162,14 @@ FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmw ...@@ -148,13 +162,14 @@ FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmw
return pluginMgr->firmwarePluginForAutopilot(firmwareType, anySupportedVehicleType); return pluginMgr->firmwarePluginForAutopilot(firmwareType, anySupportedVehicleType);
} }
QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion) QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int& majorVersion, int& minorVersion)
{ {
bool cacheHit = false; bool cacheHit = false;
FirmwarePlugin* plugin = _anyVehicleTypeFirmwarePlugin(firmwareType); int wantedMajorVersion = 1;
FirmwarePlugin* fwPlugin = _anyVehicleTypeFirmwarePlugin(firmwareType);
if (firmwareType != MAV_AUTOPILOT_PX4) { if (firmwareType != MAV_AUTOPILOT_PX4) {
return plugin->_internalParameterMetaDataFile(vehicle); return fwPlugin->_internalParameterMetaDataFile(vehicle);
} else { } else {
// Only PX4 support the old style cached metadata // Only PX4 support the old style cached metadata
QSettings settings; QSettings settings;
...@@ -164,7 +179,7 @@ QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT fi ...@@ -164,7 +179,7 @@ QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT fi
int cacheMinorVersion, cacheMajorVersion; int cacheMinorVersion, cacheMajorVersion;
QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion))); QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion)));
if (cacheFile.exists()) { if (cacheFile.exists()) {
plugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion); fwPlugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion);
if (wantedMajorVersion != cacheMajorVersion) { if (wantedMajorVersion != cacheMajorVersion) {
qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion; qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion;
} else { } else {
...@@ -196,7 +211,7 @@ QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT fi ...@@ -196,7 +211,7 @@ QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT fi
// We have a cache hit on a lower major version, read minor version as well // We have a cache hit on a lower major version, read minor version as well
int majorVersion; int majorVersion;
cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex])); cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex]));
plugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion); fwPlugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion);
if (majorVersion != cacheMajorVersion) { if (majorVersion != cacheMajorVersion) {
qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion; qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion;
cacheHit = false; cacheHit = false;
...@@ -208,8 +223,8 @@ QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT fi ...@@ -208,8 +223,8 @@ QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT fi
} }
int internalMinorVersion, internalMajorVersion; int internalMinorVersion, internalMajorVersion;
QString internalMetaDataFile = plugin->_internalParameterMetaDataFile(vehicle); QString internalMetaDataFile = fwPlugin->_internalParameterMetaDataFile(vehicle);
plugin->_getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion); fwPlugin->_getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
qCDebug(CompInfoParamLog) << "Internal metadata file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion; qCDebug(CompInfoParamLog) << "Internal metadata file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
if (cacheHit) { if (cacheHit) {
// Cache hit is available, we need to check if internal meta data is a better match, if so use internal version // Cache hit is available, we need to check if internal meta data is a better match, if so use internal version
...@@ -254,11 +269,15 @@ void CompInfoParam::_cachePX4MetaDataFile(const QString& metaDataFile) ...@@ -254,11 +269,15 @@ void CompInfoParam::_cachePX4MetaDataFile(const QString& metaDataFile)
int newMajorVersion, newMinorVersion; int newMajorVersion, newMinorVersion;
plugin->_getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion); plugin->_getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
if (newMajorVersion != 1) {
newMajorVersion = 1;
qgcApp()->showAppMessage(tr("Internal Error: Parameter MetaData major must be 1"));
}
qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile file:major;minor" << metaDataFile << newMajorVersion << newMinorVersion; qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile file:major;minor" << metaDataFile << newMajorVersion << newMinorVersion;
// Find the cache hit closest to this new file // Find the cache hit closest to this new file
int cacheMajorVersion, cacheMinorVersion; int cacheMajorVersion, cacheMinorVersion;
QString cacheHit = _parameterMetaDataFile(nullptr, MAV_AUTOPILOT_PX4, newMajorVersion, cacheMajorVersion, cacheMinorVersion); QString cacheHit = _parameterMetaDataFile(nullptr, MAV_AUTOPILOT_PX4, cacheMajorVersion, cacheMinorVersion);
qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion; qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
bool cacheNewFile = false; bool cacheNewFile = false;
...@@ -290,28 +309,19 @@ void CompInfoParam::_cachePX4MetaDataFile(const QString& metaDataFile) ...@@ -290,28 +309,19 @@ void CompInfoParam::_cachePX4MetaDataFile(const QString& metaDataFile)
} }
} }
void CompInfoParam::_parameterMajorVersionKnown(int wantedMajorVersion) QObject* CompInfoParam::_getOpaqueParameterMetaData(void)
{ {
if (_noJsonMetadata) { if (!_noJsonMetadata) {
if (_opaqueParameterMetaData) { qWarning() << "CompInfoParam::_getOpaqueParameterMetaData _noJsonMetadata == false";
return; }
}
QString metaDataFile;
int majorVersion, minorVersion;
if (!_opaqueParameterMetaData && compId == MAV_COMP_ID_AUTOPILOT1) {
// Load best parameter meta data set // Load best parameter meta data set
metaDataFile = _parameterMetaDataFile(vehicle, vehicle->firmwareType(), wantedMajorVersion, majorVersion, minorVersion); int majorVersion, minorVersion;
qCDebug(CompInfoParamLog) << "Loading meta data the old way file:major:minor" << metaDataFile << majorVersion << minorVersion; QString metaDataFile = _parameterMetaDataFile(vehicle, vehicle->firmwareType(), majorVersion, minorVersion);
qCDebug(CompInfoParamLog) << "Loading meta data the old way file" << metaDataFile;
_opaqueParameterMetaData = vehicle->firmwarePlugin()->_loadParameterMetaData(metaDataFile); _opaqueParameterMetaData = vehicle->firmwarePlugin()->_loadParameterMetaData(metaDataFile);
} }
}
void CompInfoParam::_clearPX4ParameterMetaData (void) return _opaqueParameterMetaData;
{
if (_opaqueParameterMetaData) {
qCDebug(CompInfoParamLog) << "_clearPX4ParameterMetaData";
_opaqueParameterMetaData->deleteLater();
_opaqueParameterMetaData = nullptr;
}
} }
...@@ -36,13 +36,14 @@ public: ...@@ -36,13 +36,14 @@ public:
// The following methods are used to support the old non-COMPONENT_INFORMATION based mechanism to get parameter meta data // The following methods are used to support the old non-COMPONENT_INFORMATION based mechanism to get parameter meta data
bool _isParameterVolatile (const QString& name); bool _isParameterVolatile (const QString& name);
void _parameterMajorVersionKnown(int wantedMajorVersion);
void _clearPX4ParameterMetaData (void);
static void _cachePX4MetaDataFile(const QString& metaDataFile); static void _cachePX4MetaDataFile(const QString& metaDataFile);
private: private:
QObject* _getOpaqueParameterMetaData(void);
static FirmwarePlugin* _anyVehicleTypeFirmwarePlugin (MAV_AUTOPILOT firmwareType); static FirmwarePlugin* _anyVehicleTypeFirmwarePlugin (MAV_AUTOPILOT firmwareType);
static QString _parameterMetaDataFile (Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion); static QString _parameterMetaDataFile (Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int& majorVersion, int& minorVersion);
typedef QPair<QString /* indexed name */, FactMetaData*> RegexFactMetaDataPair_t; typedef QPair<QString /* indexed name */, FactMetaData*> RegexFactMetaDataPair_t;
......
...@@ -102,7 +102,11 @@ bool ComponentInformationManager::_isCompTypeSupported(COMP_METADATA_TYPE type) ...@@ -102,7 +102,11 @@ bool ComponentInformationManager::_isCompTypeSupported(COMP_METADATA_TYPE type)
CompInfoParam* ComponentInformationManager::compInfoParam(uint8_t compId) CompInfoParam* ComponentInformationManager::compInfoParam(uint8_t compId)
{ {
return _compInfoMap.contains(compId) && _compInfoMap[compId].contains(COMP_METADATA_TYPE_PARAMETER) ? qobject_cast<CompInfoParam*>(_compInfoMap[compId][COMP_METADATA_TYPE_PARAMETER]) : nullptr; if (!_compInfoMap.contains(compId)) {
// Create default info
_compInfoMap[compId][COMP_METADATA_TYPE_PARAMETER] = new CompInfoParam(compId, _vehicle, this);
}
return qobject_cast<CompInfoParam*>(_compInfoMap[compId][COMP_METADATA_TYPE_PARAMETER]);
} }
CompInfoVersion* ComponentInformationManager::compInfoVersion(uint8_t compId) CompInfoVersion* ComponentInformationManager::compInfoVersion(uint8_t compId)
......
...@@ -601,6 +601,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -601,6 +601,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
return; return;
} }
_ftpManager->mavlinkMessageReceived(message); _ftpManager->mavlinkMessageReceived(message);
_parameterManager->mavlinkMessageReceived(message);
_waitForMavlinkMessageMessageReceived(message); _waitForMavlinkMessageMessageReceived(message);
...@@ -2616,7 +2617,7 @@ void Vehicle::_sendMavCommandWorker(bool commandInt, bool requestMessage, bool s ...@@ -2616,7 +2617,7 @@ void Vehicle::_sendMavCommandWorker(bool commandInt, bool requestMessage, bool s
emit mavCommandResult(_id, targetCompId, command, MAV_RESULT_FAILED, failureCode); emit mavCommandResult(_id, targetCompId, command, MAV_RESULT_FAILED, failureCode);
} }
if (showError) { if (showError) {
qgcApp()->showAppMessage(tr("Unabled to send command: %1. %2").arg(compIdAll ? tr("Internal error") : tr("Waiting on previous response to same command."))); qgcApp()->showAppMessage(tr("Unable to send command: %1.").arg(compIdAll ? tr("Internal error - MAV_COMP_ID_ALL not supported") : tr("Waiting on previous response to same command.")));
} }
return; return;
......
...@@ -633,7 +633,7 @@ public: ...@@ -633,7 +633,7 @@ public:
typedef enum { typedef enum {
MavCmdResultCommandResultOnly, ///< commandResult specifies full success/fail info MavCmdResultCommandResultOnly, ///< commandResult specifies full success/fail info
MavCmdResultFailureNoResponseToCommand, ///< No response from vehicle to command MavCmdResultFailureNoResponseToCommand, ///< No response from vehicle to command
MavCmdResultFailureDuplicateCommand, ///< Unabled to send command since duplicate is already being waited on for response MavCmdResultFailureDuplicateCommand, ///< Unable to send command since duplicate is already being waited on for response
} MavCmdResultFailureCode_t; } MavCmdResultFailureCode_t;
/// Callback for sendMavCommandWithHandler /// Callback for sendMavCommandWithHandler
......
...@@ -238,7 +238,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) ...@@ -238,7 +238,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
QStringList requiredKeys; QStringList requiredKeys;
requiredKeys << _jsonBoardIdKey << _jsonImageKey << _jsonImageSizeKey; requiredKeys << _jsonBoardIdKey << _jsonImageKey << _jsonImageSizeKey;
if (!JsonHelper::validateRequiredKeys(px4Json, requiredKeys, errorString)) { if (!JsonHelper::validateRequiredKeys(px4Json, requiredKeys, errorString)) {
emit statusMessage(tr("Firmware file mission required key: %1").arg(errorString)); emit statusMessage(tr("Firmware file missing required key: %1").arg(errorString));
return false; return false;
} }
......
...@@ -1567,13 +1567,15 @@ bool MockLink::_handleRequestMessage(const mavlink_command_long_t& request, bool ...@@ -1567,13 +1567,15 @@ bool MockLink::_handleRequestMessage(const mavlink_command_long_t& request, bool
switch ((int)request.param1) { switch ((int)request.param1) {
case MAVLINK_MSG_ID_COMPONENT_INFORMATION: case MAVLINK_MSG_ID_COMPONENT_INFORMATION:
switch (static_cast<int>(request.param2)) { if (_firmwareType == MAV_AUTOPILOT_PX4) {
case COMP_METADATA_TYPE_VERSION: switch (static_cast<int>(request.param2)) {
_sendVersionMetaData(); case COMP_METADATA_TYPE_VERSION:
return true; _sendVersionMetaData();
case COMP_METADATA_TYPE_PARAMETER: return true;
_sendParameterMetaData(); case COMP_METADATA_TYPE_PARAMETER:
return true; _sendParameterMetaData();
return true;
}
} }
break; break;
case MAVLINK_MSG_ID_DEBUG: case MAVLINK_MSG_ID_DEBUG:
......
...@@ -145,21 +145,6 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -145,21 +145,6 @@ void UAS::receiveMessage(mavlink_message_t message)
{ {
switch (message.msgid) switch (message.msgid)
{ {
case MAVLINK_MSG_ID_PARAM_VALUE:
{
mavlink_param_value_t rawValue;
mavlink_msg_param_value_decode(&message, &rawValue);
QByteArray bytes(rawValue.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
// Construct a string stopping at the first NUL (0) character, else copy the whole
// byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
QString parameterName(bytes);
mavlink_param_union_t paramVal;
paramVal.param_float = rawValue.param_value;
paramVal.type = rawValue.param_type;
processParamValueMsg(message, parameterName,rawValue,paramVal);
}
break;
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE: case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{ {
...@@ -524,61 +509,6 @@ quint64 UAS::getUptime() const ...@@ -524,61 +509,6 @@ quint64 UAS::getUptime() const
} }
} }
//TODO update this to use the parameter manager / param data model instead
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramUnion)
{
int compId = msg.compid;
QVariant paramValue;
// Insert with correct type
switch (rawValue.param_type) {
case MAV_PARAM_TYPE_REAL32:
paramValue = QVariant(paramUnion.param_float);
break;
case MAV_PARAM_TYPE_UINT8:
paramValue = QVariant(paramUnion.param_uint8);
break;
case MAV_PARAM_TYPE_INT8:
paramValue = QVariant(paramUnion.param_int8);
break;
case MAV_PARAM_TYPE_UINT16:
paramValue = QVariant(paramUnion.param_uint16);
break;
case MAV_PARAM_TYPE_INT16:
paramValue = QVariant(paramUnion.param_int16);
break;
case MAV_PARAM_TYPE_UINT32:
paramValue = QVariant(paramUnion.param_uint32);
break;
case MAV_PARAM_TYPE_INT32:
paramValue = QVariant(paramUnion.param_int32);
break;
//-- Note: These are not handled above:
//
// MAV_PARAM_TYPE_UINT64
// MAV_PARAM_TYPE_INT64
// MAV_PARAM_TYPE_REAL64
//
// No space in message (the only storage allocation is a "float") and not present in mavlink_param_union_t
default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
}
qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
}
/** /**
* Order the robot to start receiver pairing * Order the robot to start receiver pairing
*/ */
......
...@@ -196,8 +196,6 @@ protected: ...@@ -196,8 +196,6 @@ protected:
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */ /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
quint64 getUnixReferenceTime(quint64 time); quint64 getUnixReferenceTime(quint64 time);
virtual void processParamValueMsg(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue);
bool connectionLost; ///< Flag indicates a timed out connection bool connectionLost; ///< Flag indicates a timed out connection
quint64 connectionLossTime; ///< Time the connection was interrupted quint64 connectionLossTime; ///< Time the connection was interrupted
quint64 lastVoltageWarning; ///< Time at which the last voltage warning occurred quint64 lastVoltageWarning; ///< Time at which the last voltage warning occurred
......
...@@ -49,8 +49,6 @@ signals: ...@@ -49,8 +49,6 @@ signals:
/** @brief The robot is disconnected **/ /** @brief The robot is disconnected **/
void disconnected(); void disconnected();
void parameterUpdate(int uas, int component, QString parameterName, int parameterCount, int parameterId, int type, QVariant value);
/** /**
* @brief The battery status has been updated * @brief The battery status has been updated
* *
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
/// @file
/// @author Thomas Gubler <thomasgubler@gmail.com>
#include "QGCMapRCToParamDialog.h"
#include "ui_QGCMapRCToParamDialog.h"
#include "ParameterManager.h"
#include <QDebug>
#include <QTimer>
#include <QEventLoop>
#include <QShowEvent>
#include <QPushButton>
QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav, MultiVehicleManager* multiVehicleManager, QWidget *parent)
: QDialog(parent)
, param_id(param_id)
, mav(mav)
, _multiVehicleManager(multiVehicleManager)
, ui(new Ui::QGCMapRCToParamDialog)
{
ui->setupUi(this);
// refresh the parameter from onboard to make sure the current value is used
Vehicle* vehicle = _multiVehicleManager->getVehicleById(mav->getUASID());
Fact* paramFact = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, param_id);
ui->minValueDoubleSpinBox->setValue(paramFact->rawMin().toDouble());
ui->maxValueDoubleSpinBox->setValue(paramFact->rawMax().toDouble());
// only enable ok button when param was refreshed
QPushButton *okButton = ui->buttonBox->button(QDialogButtonBox::Ok);
okButton->setEnabled(false);
ui->paramIdLabel->setText(param_id);
connect(paramFact, &Fact::vehicleUpdated, this, &QGCMapRCToParamDialog::_parameterUpdated);
vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, param_id);
}
QGCMapRCToParamDialog::~QGCMapRCToParamDialog()
{
delete ui;
}
void QGCMapRCToParamDialog::accept() {
emit mapRCToParamDialogResult(param_id,
(float)ui->scaleDoubleSpinBox->value(),
(float)ui->value0DoubleSpinBox->value(),
(quint8)ui->rcParamChannelComboBox->currentIndex(),
(float)ui->minValueDoubleSpinBox->value(),
(float)ui->maxValueDoubleSpinBox->value());
QDialog::accept();
}
void QGCMapRCToParamDialog::_parameterUpdated(QVariant value)
{
Q_UNUSED(value);
ui->infoLabel->setText("Parameter value is up to date");
ui->value0DoubleSpinBox->setValue(value.toDouble());
ui->value0DoubleSpinBox->setEnabled(true);
connect(this, &QGCMapRCToParamDialog::mapRCToParamDialogResult, mav, &UASInterface::sendMapRCToParam);
QPushButton *okButton = ui->buttonBox->button(QDialogButtonBox::Ok);
okButton->setEnabled(true);
}
/****************************************************************************
*
* (c) 2009-2018 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.
*
****************************************************************************/
/// @file
/// @brief Dialog to configure RC to parameter mapping
/// @author Thomas Gubler <thomasgubler@gmail.com>
#pragma once
#include <QDialog>
#include <QThread>
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
#include "MultiVehicleManager.h"
namespace Ui {
class QGCMapRCToParamDialog;
}
class QGCMapRCToParamDialog : public QDialog
{
Q_OBJECT
QThread paramLoadThread;
public:
explicit QGCMapRCToParamDialog(QString param_id, UASInterface *mav, MultiVehicleManager* multiVehicleManager, QWidget *parent = 0);
~QGCMapRCToParamDialog();
signals:
void mapRCToParamDialogResult(QString param_id, float scale, float value0,
quint8 param_rc_channel_index, float valueMin, float valueMax);
public slots:
void accept();
protected:
// void showEvent(QShowEvent * event );
QString param_id;
UASInterface *mav;
private slots:
void _parameterUpdated(QVariant value);
private:
MultiVehicleManager* _multiVehicleManager;
Ui::QGCMapRCToParamDialog* ui;
};
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMapRCToParamDialog</class>
<widget class="QDialog" name="QGCMapRCToParamDialog">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>358</height>
</rect>
</property>
<property name="windowTitle">
<string>Dialog</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QFormLayout" name="formLayout">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label1">
<property name="text">
<string>Bind</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="rcParamChannelInfoLabel">
<property name="text">
<string>Parameter Tuning ID</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="rcParamChannelComboBox">
<property name="editable">
<bool>false</bool>
</property>
<property name="currentText">
<string>1</string>
</property>
<item>
<property name="text">
<string>1</string>
</property>
</item>
<item>
<property name="text">
<string>2</string>
</property>
</item>
<item>
<property name="text">
<string>3</string>
</property>
</item>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="paramIdInfoLabel">
<property name="text">
<string>Parameter</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLabel" name="paramIdLabel">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label3">
<property name="text">
<string>with</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="scaleInfoLabel">
<property name="text">
<string>Scale (keep default)</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QDoubleSpinBox" name="scaleDoubleSpinBox">
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="value0InfoLabel">
<property name="text">
<string>Center value</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QDoubleSpinBox" name="value0DoubleSpinBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="decimals">
<number>8</number>
</property>
<property name="minimum">
<double>-100000.000000000000000</double>
</property>
<property name="maximum">
<double>100000.000000000000000</double>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="minInfoLabel">
<property name="text">
<string>Minimum Value</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QDoubleSpinBox" name="minValueDoubleSpinBox">
<property name="decimals">
<number>8</number>
</property>
<property name="minimum">
<double>-100000.000000000000000</double>
</property>
<property name="maximum">
<double>100000.000000000000000</double>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QLabel" name="maxInfoLabel">
<property name="text">
<string>Maximum Value</string>
</property>
</widget>
</item>
<item row="8" column="1">
<widget class="QDoubleSpinBox" name="maxValueDoubleSpinBox">
<property name="decimals">
<number>8</number>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>100000.000000000000000</double>
</property>
<property name="singleStep">
<double>1.000000000000000</double>
</property>
<property name="value">
<double>10.000000000000000</double>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QLabel" name="infoLabel">
<property name="text">
<string>Waiting for parameter refresh,,,</string>
</property>
</widget>
</item>
<item row="9" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0" colspan="2">
<widget class="QLabel" name="label2">
<property name="text">
<string>Tuning IDs can be mapped to channels in the RC settings</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QDialogButtonBox" name="buttonBox">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="standardButtons">
<set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections>
<connection>
<sender>buttonBox</sender>
<signal>accepted()</signal>
<receiver>QGCMapRCToParamDialog</receiver>
<slot>accept()</slot>
<hints>
<hint type="sourcelabel">
<x>248</x>
<y>254</y>
</hint>
<hint type="destinationlabel">
<x>157</x>
<y>274</y>
</hint>
</hints>
</connection>
<connection>
<sender>buttonBox</sender>
<signal>rejected()</signal>
<receiver>QGCMapRCToParamDialog</receiver>
<slot>reject()</slot>
<hints>
<hint type="sourcelabel">
<x>316</x>
<y>260</y>
</hint>
<hint type="destinationlabel">
<x>286</x>
<y>274</y>
</hint>
</hints>
</connection>
</connections>
</ui>
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