Unverified Commit 9a49a206 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6904 from DonLakeFlyer/FactQGCRestartRequired

Added support for qgcRebootRequired Fact meta data value.
parents 9be76b3a 4afd9baa
...@@ -31,8 +31,7 @@ Fact::Fact(QObject* parent) ...@@ -31,8 +31,7 @@ Fact::Fact(QObject* parent)
FactMetaData* metaData = new FactMetaData(_type, this); FactMetaData* metaData = new FactMetaData(_type, this);
setMetaData(metaData); setMetaData(metaData);
// Better safe than sorry on object ownership _init();
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
} }
Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObject* parent) Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObject* parent)
...@@ -48,7 +47,8 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec ...@@ -48,7 +47,8 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
{ {
FactMetaData* metaData = new FactMetaData(_type, this); FactMetaData* metaData = new FactMetaData(_type, this);
setMetaData(metaData); setMetaData(metaData);
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
_init();
} }
Fact::Fact(const QString& settingsGroup, FactMetaData* metaData, QObject* parent) Fact::Fact(const QString& settingsGroup, FactMetaData* metaData, QObject* parent)
...@@ -64,13 +64,22 @@ Fact::Fact(const QString& settingsGroup, FactMetaData* metaData, QObject* parent ...@@ -64,13 +64,22 @@ Fact::Fact(const QString& settingsGroup, FactMetaData* metaData, QObject* parent
{ {
qgcApp()->toolbox()->corePlugin()->adjustSettingMetaData(settingsGroup, *metaData); qgcApp()->toolbox()->corePlugin()->adjustSettingMetaData(settingsGroup, *metaData);
setMetaData(metaData, true /* setDefaultFromMetaData */); setMetaData(metaData, true /* setDefaultFromMetaData */);
_init();
} }
Fact::Fact(const Fact& other, QObject* parent) Fact::Fact(const Fact& other, QObject* parent)
: QObject(parent) : QObject(parent)
{ {
*this = other; *this = other;
_init();
}
void Fact::_init(void)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
connect(this, &Fact::_containerRawValueChanged, this, &Fact::_checkForRebootMessaging);
} }
const Fact& Fact::operator=(const Fact& other) const Fact& Fact::operator=(const Fact& other)
...@@ -589,10 +598,20 @@ QVariant Fact::clamp(const QString& cookedValue) ...@@ -589,10 +598,20 @@ QVariant Fact::clamp(const QString& cookedValue)
return QVariant(); return QVariant();
} }
bool Fact::rebootRequired(void) const bool Fact::vehicleRebootRequired(void) const
{ {
if (_metaData) { if (_metaData) {
return _metaData->rebootRequired(); return _metaData->vehicleRebootRequired();
} else {
qWarning() << kMissingMetadata << name();
return false;
}
}
bool Fact::qgcRebootRequired(void) const
{
if (_metaData) {
return _metaData->qgcRebootRequired();
} else { } else {
qWarning() << kMissingMetadata << name(); qWarning() << kMissingMetadata << name();
return false; return false;
...@@ -706,3 +725,14 @@ FactValueSliderListModel* Fact::valueSliderModel(void) ...@@ -706,3 +725,14 @@ FactValueSliderListModel* Fact::valueSliderModel(void)
} }
return _valueSliderModel; return _valueSliderModel;
} }
void Fact::_checkForRebootMessaging(void)
{
if (!qgcApp()->runningUnitTests()) {
if (vehicleRebootRequired()) {
qgcApp()->showMessage(tr("Change of parameter %1 requires a Vehicle reboot to take effect.").arg(name()));
} else if (qgcRebootRequired()) {
qgcApp()->showMessage(tr("Change of '%1' value requires restart of %2 to take effect.").arg(shortDescription()).arg(qgcApp()->applicationName()));
}
}
}
...@@ -61,7 +61,8 @@ public: ...@@ -61,7 +61,8 @@ public:
Q_PROPERTY(QString minString READ cookedMinString CONSTANT) Q_PROPERTY(QString minString READ cookedMinString CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT) Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT) Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(bool rebootRequired READ rebootRequired CONSTANT) Q_PROPERTY(bool vehicleRebootRequired READ vehicleRebootRequired CONSTANT)
Q_PROPERTY(bool qgcRebootRequired READ qgcRebootRequired CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(QString units READ cookedUnits CONSTANT) Q_PROPERTY(QString units READ cookedUnits CONSTANT)
Q_PROPERTY(QVariant value READ cookedValue WRITE setCookedValue NOTIFY valueChanged) Q_PROPERTY(QVariant value READ cookedValue WRITE setCookedValue NOTIFY valueChanged)
...@@ -116,7 +117,8 @@ public: ...@@ -116,7 +117,8 @@ public:
QString rawValueString (void) const; QString rawValueString (void) const;
QString cookedValueString (void) const; QString cookedValueString (void) const;
bool valueEqualsDefault (void) const; bool valueEqualsDefault (void) const;
bool rebootRequired (void) const; bool vehicleRebootRequired (void) const;
bool qgcRebootRequired (void) const;
QString enumOrValueString (void); // This is not const, since an unknown value can modify the enum lists QString enumOrValueString (void); // This is not const, since an unknown value can modify the enum lists
double rawIncrement (void) const; double rawIncrement (void) const;
double cookedIncrement (void) const; double cookedIncrement (void) const;
...@@ -186,6 +188,12 @@ signals: ...@@ -186,6 +188,12 @@ signals:
/// ///
/// This signal is meant for use by Fact container implementations. Used to send changed values to vehicle. /// This signal is meant for use by Fact container implementations. Used to send changed values to vehicle.
void _containerRawValueChanged(const QVariant& value); void _containerRawValueChanged(const QVariant& value);
private slots:
void _checkForRebootMessaging(void);
private:
void _init(void);
protected: protected:
QString _variantToString(const QVariant& variant, int decimalPlaces) const; QString _variantToString(const QVariant& variant, int decimalPlaces) const;
......
...@@ -80,6 +80,7 @@ const char* FactMetaData::_minJsonKey = "min"; ...@@ -80,6 +80,7 @@ const char* FactMetaData::_minJsonKey = "min";
const char* FactMetaData::_maxJsonKey = "max"; const char* FactMetaData::_maxJsonKey = "max";
const char* FactMetaData::_incrementJsonKey = "increment"; const char* FactMetaData::_incrementJsonKey = "increment";
const char* FactMetaData::_hasControlJsonKey = "control"; const char* FactMetaData::_hasControlJsonKey = "control";
const char* FactMetaData::_qgcRebootRequiredJsonKey = "qgcRebootRequired";
FactMetaData::FactMetaData(QObject* parent) FactMetaData::FactMetaData(QObject* parent)
: QObject (parent) : QObject (parent)
...@@ -93,7 +94,8 @@ FactMetaData::FactMetaData(QObject* parent) ...@@ -93,7 +94,8 @@ FactMetaData::FactMetaData(QObject* parent)
, _minIsDefaultForType (true) , _minIsDefaultForType (true)
, _rawTranslator (_defaultTranslator) , _rawTranslator (_defaultTranslator)
, _cookedTranslator (_defaultTranslator) , _cookedTranslator (_defaultTranslator)
, _rebootRequired (false) , _vehicleRebootRequired(false)
, _qgcRebootRequired (false)
, _rawIncrement (std::numeric_limits<double>::quiet_NaN()) , _rawIncrement (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true) , _hasControl (true)
, _readOnly (false) , _readOnly (false)
...@@ -116,7 +118,8 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent) ...@@ -116,7 +118,8 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
, _minIsDefaultForType (true) , _minIsDefaultForType (true)
, _rawTranslator (_defaultTranslator) , _rawTranslator (_defaultTranslator)
, _cookedTranslator (_defaultTranslator) , _cookedTranslator (_defaultTranslator)
, _rebootRequired (false) , _vehicleRebootRequired(false)
, _qgcRebootRequired (false)
, _rawIncrement (std::numeric_limits<double>::quiet_NaN()) , _rawIncrement (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true) , _hasControl (true)
, _readOnly (false) , _readOnly (false)
...@@ -146,7 +149,8 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent ...@@ -146,7 +149,8 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
, _name (name) , _name (name)
, _rawTranslator (_defaultTranslator) , _rawTranslator (_defaultTranslator)
, _cookedTranslator (_defaultTranslator) , _cookedTranslator (_defaultTranslator)
, _rebootRequired (false) , _vehicleRebootRequired(false)
, _qgcRebootRequired (false)
, _rawIncrement (std::numeric_limits<double>::quiet_NaN()) , _rawIncrement (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true) , _hasControl (true)
, _readOnly (false) , _readOnly (false)
...@@ -180,7 +184,8 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other) ...@@ -180,7 +184,8 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_cookedUnits = other._cookedUnits; _cookedUnits = other._cookedUnits;
_rawTranslator = other._rawTranslator; _rawTranslator = other._rawTranslator;
_cookedTranslator = other._cookedTranslator; _cookedTranslator = other._cookedTranslator;
_rebootRequired = other._rebootRequired; _vehicleRebootRequired = other._vehicleRebootRequired;
_qgcRebootRequired = other._qgcRebootRequired;
_rawIncrement = other._rawIncrement; _rawIncrement = other._rawIncrement;
_hasControl = other._hasControl; _hasControl = other._hasControl;
_readOnly = other._readOnly; _readOnly = other._readOnly;
...@@ -363,7 +368,7 @@ bool FactMetaData::convertAndValidateRaw(const QVariant& rawValue, bool convertO ...@@ -363,7 +368,7 @@ bool FactMetaData::convertAndValidateRaw(const QVariant& rawValue, bool convertO
typedValue = QVariant(rawValue.toFloat(&convertOk)); typedValue = QVariant(rawValue.toFloat(&convertOk));
if (!convertOnly && convertOk) { if (!convertOnly && convertOk) {
if (typedValue < rawMin() || typedValue > rawMax()) { if (typedValue < rawMin() || typedValue > rawMax()) {
errorString = tr("Value must be within %1 and %2").arg(rawMin().toFloat()).arg(rawMax().toFloat()); errorString = tr("Value must be within %1 and %2").arg(rawMin().toDouble()).arg(rawMax().toDouble());
} }
} }
break; break;
...@@ -1065,15 +1070,16 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec ...@@ -1065,15 +1070,16 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
} }
QList<JsonHelper::KeyValidateInfo> keyInfoList = { QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ _nameJsonKey, QJsonValue::String, true }, { _nameJsonKey, QJsonValue::String, true },
{ _typeJsonKey, QJsonValue::String, true }, { _typeJsonKey, QJsonValue::String, true },
{ _shortDescriptionJsonKey, QJsonValue::String, false }, { _shortDescriptionJsonKey, QJsonValue::String, false },
{ _longDescriptionJsonKey, QJsonValue::String, false }, { _longDescriptionJsonKey, QJsonValue::String, false },
{ _unitsJsonKey, QJsonValue::String, false }, { _unitsJsonKey, QJsonValue::String, false },
{ _decimalPlacesJsonKey, QJsonValue::Double, false }, { _decimalPlacesJsonKey, QJsonValue::Double, false },
{ _minJsonKey, QJsonValue::Double, false }, { _minJsonKey, QJsonValue::Double, false },
{ _maxJsonKey, QJsonValue::Double, false }, { _maxJsonKey, QJsonValue::Double, false },
{ _hasControlJsonKey, QJsonValue::Bool, false }, { _hasControlJsonKey, QJsonValue::Bool, false },
{ _qgcRebootRequiredJsonKey, QJsonValue::Bool, false },
}; };
if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) { if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
qWarning() << errorString; qWarning() << errorString;
...@@ -1189,6 +1195,12 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec ...@@ -1189,6 +1195,12 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
metaData->setHasControl(true); metaData->setHasControl(true);
} }
if (json.contains(_qgcRebootRequiredJsonKey)) {
metaData->setQGCRebootRequired(json[_qgcRebootRequiredJsonKey].toBool());
} else {
metaData->setQGCRebootRequired(false);
}
return metaData; return metaData;
} }
......
...@@ -103,7 +103,8 @@ public: ...@@ -103,7 +103,8 @@ public:
ValueType_t type (void) const { return _type; } ValueType_t type (void) const { return _type; }
QString rawUnits (void) const { return _rawUnits; } QString rawUnits (void) const { return _rawUnits; }
QString cookedUnits (void) const { return _cookedUnits; } QString cookedUnits (void) const { return _cookedUnits; }
bool rebootRequired (void) const { return _rebootRequired; } bool vehicleRebootRequired (void) const { return _vehicleRebootRequired; }
bool qgcRebootRequired (void) const { return _qgcRebootRequired; }
bool hasControl (void) const { return _hasControl; } bool hasControl (void) const { return _hasControl; }
bool readOnly (void) const { return _readOnly; } bool readOnly (void) const { return _readOnly; }
bool writeOnly (void) const { return _writeOnly; } bool writeOnly (void) const { return _writeOnly; }
...@@ -123,24 +124,25 @@ public: ...@@ -123,24 +124,25 @@ public:
/// Used to add new values to the enum lists after the meta data has been loaded /// Used to add new values to the enum lists after the meta data has been loaded
void addEnumInfo(const QString& name, const QVariant& value); void addEnumInfo(const QString& name, const QVariant& value);
void setDecimalPlaces (int decimalPlaces) { _decimalPlaces = decimalPlaces; } void setDecimalPlaces (int decimalPlaces) { _decimalPlaces = decimalPlaces; }
void setRawDefaultValue (const QVariant& rawDefaultValue); void setRawDefaultValue (const QVariant& rawDefaultValue);
void setBitmaskInfo (const QStringList& strings, const QVariantList& values); void setBitmaskInfo (const QStringList& strings, const QVariantList& values);
void setEnumInfo (const QStringList& strings, const QVariantList& values); void setEnumInfo (const QStringList& strings, const QVariantList& values);
void setCategory (const QString& category) { _category = category; } void setCategory (const QString& category) { _category = category; }
void setGroup (const QString& group) { _group = group; } void setGroup (const QString& group) { _group = group; }
void setLongDescription (const QString& longDescription) { _longDescription = longDescription;} void setLongDescription (const QString& longDescription) { _longDescription = longDescription;}
void setRawMax (const QVariant& rawMax); void setRawMax (const QVariant& rawMax);
void setRawMin (const QVariant& rawMin); void setRawMin (const QVariant& rawMin);
void setName (const QString& name) { _name = name; } void setName (const QString& name) { _name = name; }
void setShortDescription(const QString& shortDescription) { _shortDescription = shortDescription; } void setShortDescription (const QString& shortDescription) { _shortDescription = shortDescription; }
void setRawUnits (const QString& rawUnits); void setRawUnits (const QString& rawUnits);
void setRebootRequired (bool rebootRequired) { _rebootRequired = rebootRequired; } void setVehicleRebootRequired (bool rebootRequired) { _vehicleRebootRequired = rebootRequired; }
void setRawIncrement (double increment) { _rawIncrement = increment; } void setQGCRebootRequired (bool rebootRequired) { _qgcRebootRequired = rebootRequired; }
void setHasControl (bool bValue) { _hasControl = bValue; } void setRawIncrement (double increment) { _rawIncrement = increment; }
void setReadOnly (bool bValue) { _readOnly = bValue; } void setHasControl (bool bValue) { _hasControl = bValue; }
void setWriteOnly (bool bValue) { _writeOnly = bValue; } void setReadOnly (bool bValue) { _readOnly = bValue; }
void setVolatileValue (bool bValue); void setWriteOnly (bool bValue) { _writeOnly = bValue; }
void setVolatileValue (bool bValue);
void setTranslators(Translator rawTranslator, Translator cookedTranslator); void setTranslators(Translator rawTranslator, Translator cookedTranslator);
...@@ -248,7 +250,8 @@ private: ...@@ -248,7 +250,8 @@ private:
QString _cookedUnits; QString _cookedUnits;
Translator _rawTranslator; Translator _rawTranslator;
Translator _cookedTranslator; Translator _cookedTranslator;
bool _rebootRequired; bool _vehicleRebootRequired;
bool _qgcRebootRequired;
double _rawIncrement; double _rawIncrement;
bool _hasControl; bool _hasControl;
bool _readOnly; bool _readOnly;
...@@ -276,18 +279,19 @@ private: ...@@ -276,18 +279,19 @@ private:
static const AppSettingsTranslation_s _rgAppSettingsTranslations[]; static const AppSettingsTranslation_s _rgAppSettingsTranslations[];
static const char* _nameJsonKey; static const char* _nameJsonKey;
static const char* _decimalPlacesJsonKey; static const char* _decimalPlacesJsonKey;
static const char* _typeJsonKey; static const char* _typeJsonKey;
static const char* _shortDescriptionJsonKey; static const char* _shortDescriptionJsonKey;
static const char* _longDescriptionJsonKey; static const char* _longDescriptionJsonKey;
static const char* _unitsJsonKey; static const char* _unitsJsonKey;
static const char* _defaultValueJsonKey; static const char* _defaultValueJsonKey;
static const char* _mobileDefaultValueJsonKey; static const char* _mobileDefaultValueJsonKey;
static const char* _minJsonKey; static const char* _minJsonKey;
static const char* _maxJsonKey; static const char* _maxJsonKey;
static const char* _incrementJsonKey; static const char* _incrementJsonKey;
static const char* _hasControlJsonKey; static const char* _hasControlJsonKey;
static const char* _qgcRebootRequiredJsonKey;
}; };
#endif #endif
...@@ -403,10 +403,6 @@ void ParameterManager::_valueUpdated(const QVariant& value) ...@@ -403,10 +403,6 @@ void ParameterManager::_valueUpdated(const QVariant& value)
_writeParameterRaw(componentId, fact->name(), value); _writeParameterRaw(componentId, fact->name(), value);
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)"; qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
qgcApp()->showMessage(tr("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
}
} }
void ParameterManager::refreshAllParameters(uint8_t componentId) void ParameterManager::refreshAllParameters(uint8_t componentId)
......
...@@ -443,7 +443,7 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) ...@@ -443,7 +443,7 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
metaData->setName(rawMetaData->name); metaData->setName(rawMetaData->name);
metaData->setCategory(rawMetaData->category); metaData->setCategory(rawMetaData->category);
metaData->setGroup(rawMetaData->group); metaData->setGroup(rawMetaData->group);
metaData->setRebootRequired(rawMetaData->rebootRequired); metaData->setVehicleRebootRequired(rawMetaData->rebootRequired);
if (!rawMetaData->shortDescription.isEmpty()) { if (!rawMetaData->shortDescription.isEmpty()) {
metaData->setShortDescription(rawMetaData->shortDescription); metaData->setShortDescription(rawMetaData->shortDescription);
......
...@@ -305,7 +305,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData ...@@ -305,7 +305,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
QString text = xml.readElementText(); QString text = xml.readElementText();
qCDebug(PX4ParameterMetaDataLog) << "RebootRequired:" << text; qCDebug(PX4ParameterMetaDataLog) << "RebootRequired:" << text;
if (text.compare("true", Qt::CaseInsensitive) == 0) { if (text.compare("true", Qt::CaseInsensitive) == 0) {
metaData->setRebootRequired(true); metaData->setVehicleRebootRequired(true);
} }
} else if (elementName == "values") { } else if (elementName == "values") {
......
...@@ -125,14 +125,15 @@ ...@@ -125,14 +125,15 @@
"defaultValue": false "defaultValue": false
}, },
{ {
"name": "BaseDeviceFontPointSize", "name": "BaseDeviceFontPointSize",
"shortDescription": "Application font size", "shortDescription": "Application font size",
"longDescription": "The point size for the default font used.", "longDescription": "The point size for the default font used.",
"type": "uint32", "type": "uint32",
"units": "pt", "units": "pt",
"min": 6, "min": 6,
"max": 48, "max": 48,
"defaultValue": 0 "defaultValue": 0,
"qgcRebootRequired": true
}, },
{ {
"name": "StyleIsDark", "name": "StyleIsDark",
......
[ [
{ {
"name": "SurveyInAccuracyLimit", "name": "SurveyInAccuracyLimit",
"shortDescription": "Survey in accuracy limit", "shortDescription": "Survey in accuracy (U-blox only)",
"longDescription": "The maximum accuracy allowed prior to completing survey in.", "longDescription": "The maximum accuracy allowed prior to completing survey in.",
"type": "double", "type": "double",
"defaultValue": 2.0, "defaultValue": 2.0,
"min": 0.5, "min": 0.5,
"units": "m", "units": "m",
"decimalPlaces": 1 "decimalPlaces": 1,
"qgcRebootRequired": true
}, },
{ {
"name": "SurveyInMinObservationDuration", "name": "SurveyInMinObservationDuration",
"shortDescription": "Minimum observation time", "shortDescription": "Minimum observation time",
"longDescription": "Defines the minimum amount of observation time for the position calculation.", "longDescription": "Defines the minimum amount of observation time for the position calculation.",
"type": "Uint32", "type": "Uint32",
"defaultValue": 180, "defaultValue": 180,
"min": 1, "min": 1,
"units": "secs", "units": "secs",
"decimalPlaces": 0 "decimalPlaces": 0,
"qgcRebootRequired": true
} }
] ]
...@@ -43,8 +43,10 @@ Fact* UnitsSettings::distanceUnits(void) ...@@ -43,8 +43,10 @@ Fact* UnitsSettings::distanceUnits(void)
FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
metaData->setName(distanceUnitsSettingsName); metaData->setName(distanceUnitsSettingsName);
metaData->setShortDescription(tr("Distance units"));
metaData->setEnumInfo(enumStrings, enumValues); metaData->setEnumInfo(enumStrings, enumValues);
metaData->setRawDefaultValue(DistanceUnitsMeters); metaData->setRawDefaultValue(DistanceUnitsMeters);
metaData->setQGCRebootRequired(true);
_distanceUnitsFact = new SettingsFact(_settingsGroup, metaData, this); _distanceUnitsFact = new SettingsFact(_settingsGroup, metaData, this);
...@@ -66,8 +68,10 @@ Fact* UnitsSettings::areaUnits(void) ...@@ -66,8 +68,10 @@ Fact* UnitsSettings::areaUnits(void)
FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
metaData->setName(areaUnitsSettingsName); metaData->setName(areaUnitsSettingsName);
metaData->setShortDescription(tr("Area units"));
metaData->setEnumInfo(enumStrings, enumValues); metaData->setEnumInfo(enumStrings, enumValues);
metaData->setRawDefaultValue(AreaUnitsSquareMeters); metaData->setRawDefaultValue(AreaUnitsSquareMeters);
metaData->setQGCRebootRequired(true);
_areaUnitsFact = new SettingsFact(_settingsGroup, metaData, this); _areaUnitsFact = new SettingsFact(_settingsGroup, metaData, this);
} }
...@@ -88,8 +92,10 @@ Fact* UnitsSettings::speedUnits(void) ...@@ -88,8 +92,10 @@ Fact* UnitsSettings::speedUnits(void)
FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
metaData->setName(speedUnitsSettingsName); metaData->setName(speedUnitsSettingsName);
metaData->setShortDescription(tr("Speed units"));
metaData->setEnumInfo(enumStrings, enumValues); metaData->setEnumInfo(enumStrings, enumValues);
metaData->setRawDefaultValue(SpeedUnitsMetersPerSecond); metaData->setRawDefaultValue(SpeedUnitsMetersPerSecond);
metaData->setQGCRebootRequired(true);
_speedUnitsFact = new SettingsFact(_settingsGroup, metaData, this); _speedUnitsFact = new SettingsFact(_settingsGroup, metaData, this);
} }
...@@ -109,8 +115,10 @@ Fact* UnitsSettings::temperatureUnits(void) ...@@ -109,8 +115,10 @@ Fact* UnitsSettings::temperatureUnits(void)
FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
metaData->setName(temperatureUnitsSettingsName); metaData->setName(temperatureUnitsSettingsName);
metaData->setShortDescription(tr("Temperature units"));
metaData->setEnumInfo(enumStrings, enumValues); metaData->setEnumInfo(enumStrings, enumValues);
metaData->setRawDefaultValue(TemperatureUnitsCelsius); metaData->setRawDefaultValue(TemperatureUnitsCelsius);
metaData->setQGCRebootRequired(true);
_temperatureUnitsFact = new SettingsFact(_settingsGroup, metaData, this); _temperatureUnitsFact = new SettingsFact(_settingsGroup, metaData, this);
} }
......
...@@ -38,7 +38,7 @@ QGCView { ...@@ -38,7 +38,7 @@ QGCView {
property Fact _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor property Fact _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor
property real _labelWidth: ScreenTools.defaultFontPixelWidth * 20 property real _labelWidth: ScreenTools.defaultFontPixelWidth * 20
property real _comboFieldWidth: ScreenTools.defaultFontPixelWidth * 25 property real _comboFieldWidth: ScreenTools.defaultFontPixelWidth * 25
property real _valueFieldWidth: ScreenTools.defaultFontPixelWidth * 8 property real _valueFieldWidth: ScreenTools.defaultFontPixelWidth * 10
property Fact _mapProvider: QGroundControl.settingsManager.flightMapSettings.mapProvider property Fact _mapProvider: QGroundControl.settingsManager.flightMapSettings.mapProvider
property Fact _mapType: QGroundControl.settingsManager.flightMapSettings.mapType property Fact _mapType: QGroundControl.settingsManager.flightMapSettings.mapType
property Fact _followTarget: QGroundControl.settingsManager.appSettings.followTarget property Fact _followTarget: QGroundControl.settingsManager.appSettings.followTarget
...@@ -47,8 +47,6 @@ QGCView { ...@@ -47,8 +47,6 @@ QGCView {
readonly property real _internalWidthRatio: 0.8 readonly property real _internalWidthRatio: 0.8
readonly property string _requiresRestart: qsTr("(Requires Restart)")
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
QGCViewPanel { QGCViewPanel {
...@@ -72,7 +70,7 @@ QGCView { ...@@ -72,7 +70,7 @@ QGCView {
QGCLabel { QGCLabel {
id: unitsSectionLabel id: unitsSectionLabel
text: qsTr("Units (Requires Restart)") text: qsTr("Units")
visible: QGroundControl.settingsManager.unitsSettings.visible visible: QGroundControl.settingsManager.unitsSettings.visible
} }
Rectangle { Rectangle {
...@@ -233,9 +231,6 @@ QGCView { ...@@ -233,9 +231,6 @@ QGCView {
} }
} }
} }
QGCLabel {
text: _requiresRestart
}
} }
...@@ -384,7 +379,7 @@ QGCView { ...@@ -384,7 +379,7 @@ QGCView {
QGCLabel { QGCLabel {
id: rtkSectionLabel id: rtkSectionLabel
text: qsTr("RTK GPS (Requires Restart)") text: qsTr("RTK GPS")
visible: QGroundControl.settingsManager.rtkSettings.visible visible: QGroundControl.settingsManager.rtkSettings.visible
} }
Rectangle { Rectangle {
...@@ -402,16 +397,18 @@ QGCView { ...@@ -402,16 +397,18 @@ QGCView {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
columns: 2 columns: 2
QGCLabel { text: qsTr("Survey in accuracy (U-blox only)") } property var rtkSettings: QGroundControl.settingsManager.rtkSettings
QGCLabel { text: rtkGrid.rtkSettings.surveyInAccuracyLimit.shortDescription }
FactTextField { FactTextField {
Layout.preferredWidth: _valueFieldWidth Layout.preferredWidth: _valueFieldWidth
fact: QGroundControl.settingsManager.rtkSettings.surveyInAccuracyLimit fact: rtkGrid.rtkSettings.surveyInAccuracyLimit
} }
QGCLabel { text: qsTr("Minimum observation duration") } QGCLabel { text: rtkGrid.rtkSettings.surveyInMinObservationDuration.shortDescription }
FactTextField { FactTextField {
Layout.preferredWidth: _valueFieldWidth Layout.preferredWidth: _valueFieldWidth
fact: QGroundControl.settingsManager.rtkSettings.surveyInMinObservationDuration fact: rtkGrid.rtkSettings.surveyInMinObservationDuration
} }
} }
} }
......
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