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