Commit d1828fe5 authored by Gus Grubba's avatar Gus Grubba

Reset Parameters to Vehicle's Default

parent 168bc8ec
...@@ -1109,8 +1109,8 @@ void ParameterManager::_checkInitialLoadComplete(void) ...@@ -1109,8 +1109,8 @@ void ParameterManager::_checkInitialLoadComplete(void)
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete // We aren't waiting for any more initial parameter updates, initial parameter loading is complete
_initialLoadComplete = true; _initialLoadComplete = true;
// Parameter cache crc failure debugging // Parameter cache crc failure debugging
for (int componentId: _debugCacheParamSeen.keys()) { for (int componentId: _debugCacheParamSeen.keys()) {
if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) { if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
for (const QString& paramName: _debugCacheParamSeen[componentId].keys()) { for (const QString& paramName: _debugCacheParamSeen[componentId].keys()) {
if (!_debugCacheParamSeen[componentId][paramName]) { if (!_debugCacheParamSeen[componentId][paramName]) {
...@@ -1363,7 +1363,7 @@ QString ParameterManager::_remapParamNameToVersion(const QString& paramName) ...@@ -1363,7 +1363,7 @@ QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
/// The offline editing vehicle can have custom loaded params bolted into it. /// The offline editing vehicle can have custom loaded params bolted into it.
void ParameterManager::_loadOfflineEditingParams(void) void ParameterManager::_loadOfflineEditingParams(void)
{ {
QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle); QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
if (paramFilename.isEmpty()) { if (paramFilename.isEmpty()) {
return; return;
...@@ -1542,7 +1542,7 @@ bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QStr ...@@ -1542,7 +1542,7 @@ bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QStr
return true; return true;
} }
void ParameterManager::resetAllParametersToDefaults(void) void ParameterManager::resetAllParametersToDefaults()
{ {
_vehicle->sendMavCommand(MAV_COMP_ID_ALL, _vehicle->sendMavCommand(MAV_COMP_ID_ALL,
MAV_CMD_PREFLIGHT_STORAGE, MAV_CMD_PREFLIGHT_STORAGE,
...@@ -1551,6 +1551,15 @@ void ParameterManager::resetAllParametersToDefaults(void) ...@@ -1551,6 +1551,15 @@ void ParameterManager::resetAllParametersToDefaults(void)
-1); // Don't do anything with mission storage -1); // Don't do anything with mission storage
} }
void ParameterManager::resetAllToVehicleConfiguration()
{
//-- https://github.com/PX4/Firmware/pull/11760
Fact* sysAutoConfigFact = getParameter(-1, "SYS_AUTOCONFIG");
if(sysAutoConfigFact) {
sysAutoConfigFact->setRawValue(2);
}
}
QString ParameterManager::_logVehiclePrefix(int componentId) QString ParameterManager::_logVehiclePrefix(int componentId)
{ {
if (componentId == -1) { if (componentId == -1) {
...@@ -1563,7 +1572,7 @@ QString ParameterManager::_logVehiclePrefix(int componentId) ...@@ -1563,7 +1572,7 @@ QString ParameterManager::_logVehiclePrefix(int componentId)
void ParameterManager::_setLoadProgress(double loadProgress) void ParameterManager::_setLoadProgress(double loadProgress)
{ {
_loadProgress = loadProgress; _loadProgress = loadProgress;
emit loadProgressChanged(loadProgress); emit loadProgressChanged(static_cast<float>(loadProgress));
} }
QList<int> ParameterManager::componentIds(void) QList<int> ParameterManager::componentIds(void)
......
...@@ -30,7 +30,7 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog) ...@@ -30,7 +30,7 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
class ParameterManager : public QObject class ParameterManager : public QObject
{ {
Q_OBJECT Q_OBJECT
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);
...@@ -51,37 +51,38 @@ public: ...@@ -51,37 +51,38 @@ public:
static QString parameterCacheFile(int vehicleId, int componentId); static QString parameterCacheFile(int vehicleId, int componentId);
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
void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL); void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
/// Request a refresh on the specific parameter /// Request a refresh on the specific parameter
void refreshParameter(int componentId, const QString& name); void refreshParameter(int componentId, const QString& name);
/// Request a refresh on all parameters that begin with the specified prefix /// Request a refresh on all parameters that begin with the specified prefix
void refreshParametersPrefix(int componentId, const QString& namePrefix); void refreshParametersPrefix(int componentId, const QString& namePrefix);
void resetAllParametersToDefaults(void); void resetAllParametersToDefaults();
void resetAllToVehicleConfiguration();
/// Returns true if the specifed parameter exists /// Returns true if the specifed parameter exists
/// @param componentId Component id or FactSystem::defaultComponentId /// @param componentId Component id or FactSystem::defaultComponentId
/// @param name Parameter name /// @param name Parameter name
bool parameterExists(int componentId, const QString& name); bool parameterExists(int componentId, const QString& name);
/// Returns all parameter names /// Returns all parameter names
QStringList parameterNames(int componentId); QStringList parameterNames(int componentId);
/// Returns the specified Parameter. Returns a default empty fact is parameter does not exists. Also will pop /// Returns the specified Parameter. Returns a default empty fact is parameter does not exists. Also will pop
/// a missing parameter error to user if parameter does not exist. /// a missing parameter error to user if parameter does not exist.
/// @param componentId Component id or FactSystem::defaultComponentId /// @param componentId Component id or FactSystem::defaultComponentId
/// @param name Parameter name /// @param name Parameter name
Fact* getParameter(int componentId, const QString& name); Fact* getParameter(int componentId, const QString& name);
const QMap<QString, QMap<QString, QStringList> >& getDefaultComponentCategoryMap(void); const QMap<QString, QMap<QString, QStringList> >& getDefaultComponentCategoryMap(void);
/// 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 /// Returns the version number for the parameter set, -1 if not known
...@@ -116,11 +117,11 @@ signals: ...@@ -116,11 +117,11 @@ 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);
protected: protected:
Vehicle* _vehicle; Vehicle* _vehicle;
MAVLinkProtocol* _mavlink; MAVLinkProtocol* _mavlink;
void _parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value); void _parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
void _valueUpdated(const QVariant& value); void _valueUpdated(const QVariant& value);
void _waitingParamTimeout(void); void _waitingParamTimeout(void);
...@@ -154,7 +155,7 @@ private: ...@@ -154,7 +155,7 @@ private:
// Category map of default component parameters // Category map of default component parameters
QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _defaultComponentCategoryMap; QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _defaultComponentCategoryMap;
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
bool _missingParameters; ///< true: parameter missing from initial load bool _missingParameters; ///< true: parameter missing from initial load
...@@ -195,12 +196,12 @@ private: ...@@ -195,12 +196,12 @@ private:
QMap<int, QList<int> > _failedReadParamIndexMap; ///< Key: Component id, Value: failed parameter index QMap<int, QList<int> > _failedReadParamIndexMap; ///< Key: Component id, Value: failed parameter index
int _totalParamCount; ///< Number of parameters across all components int _totalParamCount; ///< Number of parameters across all components
QTimer _initialRequestTimeoutTimer; QTimer _initialRequestTimeoutTimer;
QTimer _waitingParamTimeoutTimer; QTimer _waitingParamTimeoutTimer;
QMutex _dataMutex; QMutex _dataMutex;
Fact _defaultFact; ///< Used to return default fact, when parameter not found Fact _defaultFact; ///< Used to return default fact, when parameter not found
static const char* _cachedMetaDataFilePrefix; static const char* _cachedMetaDataFilePrefix;
......
...@@ -98,48 +98,55 @@ Item { ...@@ -98,48 +98,55 @@ Item {
anchors.right: parent.right anchors.right: parent.right
text: qsTr("Tools") text: qsTr("Tools")
visible: !_searchFilter visible: !_searchFilter
onClicked: toolsMenu.popup()
}
menu: Menu { Menu {
MenuItem { id: toolsMenu
text: qsTr("Refresh") MenuItem {
onTriggered: controller.refresh() text: qsTr("Refresh")
} onTriggered: controller.refresh()
MenuItem { }
text: qsTr("Reset all to defaults") MenuItem {
visible: !activeVehicle.apmFirmware text: qsTr("Reset all to firmware's defaults")
onTriggered: mainWindow.showDialog(resetToDefaultConfirmComponent, qsTr("Reset All"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Reset) visible: !activeVehicle.apmFirmware
} onTriggered: mainWindow.showDialog(resetToDefaultConfirmComponent, qsTr("Reset All"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Reset)
MenuSeparator { } }
MenuItem { MenuItem {
text: qsTr("Load from file...") text: qsTr("Reset to vehicle's configuration defaults")
onTriggered: { visible: !activeVehicle.apmFirmware
fileDialog._root = _root onTriggered: mainWindow.showDialog(resetToVehicleConfigurationConfirmComponent, qsTr("Reset All"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Reset)
fileDialog.title = qsTr("Load Parameters") }
fileDialog.selectExisting = true MenuSeparator { }
fileDialog.openForLoad() MenuItem {
} text: qsTr("Load from file...")
} onTriggered: {
MenuItem { fileDialog._root = _root
text: qsTr("Save to file...") fileDialog.title = qsTr("Load Parameters")
onTriggered: { fileDialog.selectExisting = true
fileDialog._root = _root fileDialog.openForLoad()
fileDialog.title = qsTr("Save Parameters")
fileDialog.selectExisting = false
fileDialog.openForSave()
}
}
MenuSeparator { visible: _showRCToParam }
MenuItem {
text: qsTr("Clear RC to Param")
onTriggered: controller.clearRCToParam()
visible: _showRCToParam
} }
MenuSeparator { } }
MenuItem { MenuItem {
text: qsTr("Reboot Vehicle") text: qsTr("Save to file...")
onTriggered: mainWindow.showDialog(rebootVehicleConfirmComponent, qsTr("Reboot Vehicle"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) onTriggered: {
fileDialog._root = _root
fileDialog.title = qsTr("Save Parameters")
fileDialog.selectExisting = false
fileDialog.openForSave()
} }
} }
MenuSeparator { visible: _showRCToParam }
MenuItem {
text: qsTr("Clear RC to Param")
onTriggered: controller.clearRCToParam()
visible: _showRCToParam
}
MenuSeparator { }
MenuItem {
text: qsTr("Reboot Vehicle")
onTriggered: mainWindow.showDialog(rebootVehicleConfirmComponent, qsTr("Reboot Vehicle"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
}
} }
/// Group buttons /// Group buttons
...@@ -309,13 +316,11 @@ Item { ...@@ -309,13 +316,11 @@ Item {
Component { Component {
id: resetToDefaultConfirmComponent id: resetToDefaultConfirmComponent
QGCViewDialog { QGCViewDialog {
function accept() { function accept() {
controller.resetAllToDefaults() controller.resetAllToDefaults()
hideDialog() hideDialog()
} }
QGCLabel { QGCLabel {
width: parent.width width: parent.width
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
...@@ -324,6 +329,21 @@ Item { ...@@ -324,6 +329,21 @@ Item {
} }
} }
Component {
id: resetToVehicleConfigurationConfirmComponent
QGCViewDialog {
function accept() {
controller.resetAllToVehicleConfiguration()
hideDialog()
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Select Reset to reset all parameters to the vehicle's configuration defaults.")
}
}
}
Component { Component {
id: rebootVehicleConfirmComponent id: rebootVehicleConfirmComponent
......
...@@ -54,7 +54,7 @@ ParameterEditorController::ParameterEditorController(void) ...@@ -54,7 +54,7 @@ ParameterEditorController::ParameterEditorController(void)
ParameterEditorController::~ParameterEditorController() ParameterEditorController::~ParameterEditorController()
{ {
} }
QStringList ParameterEditorController::getGroupsForCategory(const QString& category) QStringList ParameterEditorController::getGroupsForCategory(const QString& category)
...@@ -71,13 +71,13 @@ QStringList ParameterEditorController::getGroupsForCategory(const QString& categ ...@@ -71,13 +71,13 @@ QStringList ParameterEditorController::getGroupsForCategory(const QString& categ
QStringList ParameterEditorController::searchParameters(const QString& searchText, bool searchInName, bool searchInDescriptions) QStringList ParameterEditorController::searchParameters(const QString& searchText, bool searchInName, bool searchInDescriptions)
{ {
QStringList list; QStringList list;
for(const QString &paramName: _parameterMgr->parameterNames(_vehicle->defaultComponentId())) { for(const QString &paramName: _parameterMgr->parameterNames(_vehicle->defaultComponentId())) {
if (searchText.isEmpty()) { if (searchText.isEmpty()) {
list += paramName; list += paramName;
} else { } else {
Fact* fact = _parameterMgr->getParameter(_vehicle->defaultComponentId(), paramName); Fact* fact = _parameterMgr->getParameter(_vehicle->defaultComponentId(), paramName);
if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) { if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) {
list += paramName; list += paramName;
} else if (searchInDescriptions && (fact->shortDescription().contains(searchText, Qt::CaseInsensitive) || fact->longDescription().contains(searchText, Qt::CaseInsensitive))) { } else if (searchInDescriptions && (fact->shortDescription().contains(searchText, Qt::CaseInsensitive) || fact->longDescription().contains(searchText, Qt::CaseInsensitive))) {
...@@ -86,7 +86,7 @@ QStringList ParameterEditorController::searchParameters(const QString& searchTex ...@@ -86,7 +86,7 @@ QStringList ParameterEditorController::searchParameters(const QString& searchTex
} }
} }
list.sort(); list.sort();
return list; return list;
} }
...@@ -106,12 +106,12 @@ void ParameterEditorController::saveToFile(const QString& filename) ...@@ -106,12 +106,12 @@ void ParameterEditorController::saveToFile(const QString& filename)
} }
QFile file(parameterFilename); QFile file(parameterFilename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
qgcApp()->showMessage(tr("Unable to create file: %1").arg(parameterFilename)); qgcApp()->showMessage(tr("Unable to create file: %1").arg(parameterFilename));
return; return;
} }
QTextStream stream(&file); QTextStream stream(&file);
_parameterMgr->writeParametersToStream(stream); _parameterMgr->writeParametersToStream(stream);
file.close(); file.close();
...@@ -121,19 +121,19 @@ void ParameterEditorController::saveToFile(const QString& filename) ...@@ -121,19 +121,19 @@ void ParameterEditorController::saveToFile(const QString& filename)
void ParameterEditorController::loadFromFile(const QString& filename) void ParameterEditorController::loadFromFile(const QString& filename)
{ {
QString errors; QString errors;
if (!filename.isEmpty()) { if (!filename.isEmpty()) {
QFile file(filename); QFile file(filename);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
qgcApp()->showMessage(tr("Unable to open file: %1").arg(filename)); qgcApp()->showMessage(tr("Unable to open file: %1").arg(filename));
return; return;
} }
QTextStream stream(&file); QTextStream stream(&file);
errors = _parameterMgr->readParametersFromStream(stream); errors = _parameterMgr->readParametersFromStream(stream);
file.close(); file.close();
if (!errors.isEmpty()) { if (!errors.isEmpty()) {
emit showErrorMessage(errors); emit showErrorMessage(errors);
} }
...@@ -151,6 +151,12 @@ void ParameterEditorController::resetAllToDefaults(void) ...@@ -151,6 +151,12 @@ void ParameterEditorController::resetAllToDefaults(void)
refresh(); refresh();
} }
void ParameterEditorController::resetAllToVehicleConfiguration(void)
{
_parameterMgr->resetAllToVehicleConfiguration();
refresh();
}
void ParameterEditorController::setRCToParam(const QString& paramName) void ParameterEditorController::setRCToParam(const QString& paramName)
{ {
#ifdef __mobile__ #ifdef __mobile__
......
...@@ -26,7 +26,7 @@ ...@@ -26,7 +26,7 @@
class ParameterEditorController : public FactPanelController class ParameterEditorController : public FactPanelController
{ {
Q_OBJECT Q_OBJECT
public: public:
ParameterEditorController(void); ParameterEditorController(void);
~ParameterEditorController(); ~ParameterEditorController();
...@@ -40,16 +40,17 @@ public: ...@@ -40,16 +40,17 @@ public:
Q_INVOKABLE QStringList getGroupsForCategory(const QString& category); Q_INVOKABLE QStringList getGroupsForCategory(const QString& category);
Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true); Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true);
Q_INVOKABLE void clearRCToParam(void); Q_INVOKABLE void clearRCToParam(void);
Q_INVOKABLE void saveToFile(const QString& filename); Q_INVOKABLE void saveToFile(const QString& filename);
Q_INVOKABLE void loadFromFile(const QString& filename); Q_INVOKABLE void loadFromFile(const QString& filename);
Q_INVOKABLE void refresh(void); Q_INVOKABLE void refresh(void);
Q_INVOKABLE void resetAllToDefaults(void); Q_INVOKABLE void resetAllToDefaults(void);
Q_INVOKABLE void resetAllToVehicleConfiguration(void);
Q_INVOKABLE void setRCToParam(const QString& paramName); Q_INVOKABLE void setRCToParam(const QString& paramName);
QList<QObject*> model(void); QList<QObject*> model(void);
signals: signals:
void searchTextChanged(QString searchText); void searchTextChanged(QString searchText);
void currentCategoryChanged(QString category); void currentCategoryChanged(QString category);
......
...@@ -97,10 +97,10 @@ Item { ...@@ -97,10 +97,10 @@ Item {
id: _dialogPanel id: _dialogPanel
anchors.fill: parent anchors.fill: parent
Rectangle { Rectangle {
id: _header id: _header
width: parent.width width: parent.width
height: _acceptButton.visible ? _acceptButton.height : _rejectButton.height height: _acceptButton.visible ? _acceptButton.height : _rejectButton.height
color: qgcPal.windowShade color: qgcPal.windowShade
QGCLabel { QGCLabel {
id: titleLabel id: titleLabel
x: _defaultTextWidth x: _defaultTextWidth
...@@ -109,18 +109,19 @@ Item { ...@@ -109,18 +109,19 @@ Item {
verticalAlignment: Text.AlignVCenter verticalAlignment: Text.AlignVCenter
} }
QGCButton { QGCButton {
id: _rejectButton id: _rejectButton
anchors.right: _acceptButton.visible ? _acceptButton.left : parent.right anchors.right: _acceptButton.visible ? _acceptButton.left : parent.right
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
onClicked: { onClicked: {
_dialogComponentLoader.item.reject() _dialogComponentLoader.item.reject()
mainWindowDialog.close() mainWindowDialog.close()
} }
} }
QGCButton { QGCButton {
id: _acceptButton id: _acceptButton
anchors.right: parent.right anchors.right: parent.right
primary: true anchors.bottom: parent.bottom
primary: true
onClicked: { onClicked: {
_dialogComponentLoader.item.accept() _dialogComponentLoader.item.accept()
mainWindowDialog.close() mainWindowDialog.close()
...@@ -128,10 +129,10 @@ Item { ...@@ -128,10 +129,10 @@ Item {
} }
} }
Item { Item {
id: _spacer id: _spacer
width: 10 width: 10
height: 10 height: 10
anchors.top: _header.bottom anchors.top: _header.bottom
} }
Loader { Loader {
id: _dialogComponentLoader id: _dialogComponentLoader
......
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