Commit aa490d2c authored by Gus Grubba's avatar Gus Grubba

Added the concept of a read only parameter.

Removed guess work from what parameters must be refreshed/updated when some other parameter changes. Added a "reset" flag that indicates when a certain parameter changes, the list must be reloaded.
Don't send a signal when setting a fact if the new value is the same.
parent c5fc519e
......@@ -31,6 +31,7 @@ static const char* kStrings = "strings";
static const char* kName = "name";
static const char* kValue = "value";
static const char* kControl = "control";
static const char* kReadOnly = "readonly";
static const char* kOptions = "options";
static const char* kOption = "option";
static const char* kType = "type";
......@@ -44,6 +45,7 @@ static const char* kParameterranges = "parameterranges";
static const char* kParameterrange = "parameterrange";
static const char* kOriginal = "original";
static const char* kTranslated = "translated";
static const char* kReset = "reset";
//-----------------------------------------------------------------------------
static bool
......@@ -523,22 +525,38 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
qCritical() << QString("Parameter %1 missing parameter type").arg(factName);
return false;
}
//-- Does it have a control?
bool control = true;
read_attribute(parameterNode, kControl, control);
//-- Is it read only?
bool readOnly = false;
read_attribute(parameterNode, kReadOnly, readOnly);
//-- Param type
bool unknownType;
FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
if (unknownType) {
qCritical() << QString("Unknown type for parameter %1").arg(factName);
return false;
}
//-- Description
QString description;
if(!read_value(parameterNode, kDescription, description)) {
qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
return false;
}
//-- Does it require full update on changes?
bool update = false;
read_attribute(parameterNode, kReset, update);
if(update) {
_requestUpdates << factName;
}
//-- Build metadata
FactMetaData* metaData = new FactMetaData(factType, factName, this);
QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
metaData->setShortDescription(description);
metaData->setLongDescription(description);
metaData->setHasControl(control);
metaData->setReadOnly(readOnly);
//-- Options (enums)
QDomElement optionElem = parameterNode.toElement();
QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions);
......@@ -875,7 +893,6 @@ QGCCameraControl::_updateRanges(Fact* pFact)
{
QMap<Fact*, QGCCameraOptionRange*> rangesSet;
QMap<Fact*, QString> rangesReset;
QStringList valuesRequested;
QStringList changedList;
QStringList resetList;
//-- Iterate range sets looking for limited ranges
......@@ -885,20 +902,15 @@ QGCCameraControl::_updateRanges(Fact* pFact)
Fact* pRFact = getFact(pRange->param); //-- This parameter
Fact* pTFact = getFact(pRange->targetParam); //-- The target parameter (the one its range is to change)
if(pRFact && pTFact) {
qCDebug(CameraControlLogVerbose) << "Check new set of options for" << pTFact->name();
//qCDebug(CameraControlLogVerbose) << "Check new set of options for" << pTFact->name();
QString option = pRFact->rawValueString(); //-- This parameter value
//-- If this value (and condition) triggers a change in the target range
qCDebug(CameraControlLogVerbose) << "Range value:" << pRange->value << "Current value:" << option << "Condition:" << pRange->condition;
//qCDebug(CameraControlLogVerbose) << "Range value:" << pRange->value << "Current value:" << option << "Condition:" << pRange->condition;
if(pRange->value == option && _processCondition(pRange->condition)) {
if(pTFact->enumStrings() != pRange->optNames) {
//-- Set limited range set
rangesSet[pTFact] = pRange;
//-- Get setting if current index is outside new limts
if(!pRange->optVariants.contains(pTFact->rawValue()) && _activeSettings.contains(pTFact->name())) {
//-- We need to preemt the new option
valuesRequested << pTFact->name();
}
qCDebug(CameraControlLogVerbose) << "Limited:" << pRange->targetParam << pRange->optNames;
qCDebug(CameraControlLogVerbose) << "Limited set of options for:" << pRange->targetParam << pRange->optNames;
}
changedList << pRange->targetParam;
}
......@@ -913,11 +925,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
if(pTFact->enumStrings() != _originalOptNames[pRange->targetParam]) {
//-- Restore full option set
rangesReset[pTFact] = pRange->targetParam;
qCDebug(CameraControlLogVerbose) << "Restore full set:" << pRange->targetParam << _originalOptNames[pRange->targetParam];
//-- Retrive the current option for this setting as the index into the options might be pointing to something else.
if(!valuesRequested.contains(pTFact->name())) {
valuesRequested << pTFact->name();
}
qCDebug(CameraControlLogVerbose) << "Restore full set of options for:" << pRange->targetParam << _originalOptNames[pRange->targetParam];
}
resetList << pRange->targetParam;
}
......@@ -941,9 +949,9 @@ QGCCameraControl::_updateRanges(Fact* pFact)
_updates << pFact;
}
}
//-- Update values for restored/limited ranges
foreach (QString factName, valuesRequested) {
_paramIO[factName]->paramRequest();
//-- Parameter update requests
if(_requestUpdates.contains(pFact->name())) {
_requestAllParameters();
}
//-- Update UI (Asynchronous state where values come back after a while)
if(_updates.size()) {
......
......@@ -213,4 +213,6 @@ protected:
QMap<QString, QVariantList> _originalOptValues;
QMap<QString, QGCCameraParamIO*> _paramIO;
QVector<Fact*> _updates;
//-- Parameters that require a full update
QStringList _requestUpdates;
};
......@@ -26,7 +26,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
_paramWriteTimer.setSingleShot(true);
_paramWriteTimer.setInterval(3000);
_paramRequestTimer.setSingleShot(true);
_paramRequestTimer.setInterval(3000);
_paramRequestTimer.setInterval(3500);
connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
......@@ -76,7 +76,7 @@ void
QGCCameraParamIO::_factChanged(QVariant value)
{
Q_UNUSED(value);
qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed";
qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed to" << value;
//-- TODO: Do we really want to update the UI now or only when we receive the ACK?
_control->factChanged(_fact);
}
......@@ -85,10 +85,12 @@ QGCCameraParamIO::_factChanged(QVariant value)
void
QGCCameraParamIO::_containerRawValueChanged(const QVariant value)
{
Q_UNUSED(value);
qCDebug(CameraIOLog) << "Update Fact" << _fact->name();
_sentRetries = 0;
_sendParameter();
if(!_fact->readOnly()) {
Q_UNUSED(value);
qCDebug(CameraIOLog) << "Update Fact" << _fact->name();
_sentRetries = 0;
_sendParameter();
}
}
//-----------------------------------------------------------------------------
......
......@@ -85,8 +85,8 @@ void Fact::forceSetRawValue(const QVariant& value)
_rawValue.setValue(typedValue);
_sendValueChangedSignal(cookedValue());
//-- Must be in this order
emit rawValueChanged(_rawValue);
emit _containerRawValueChanged(rawValue());
emit rawValueChanged(_rawValue);
}
} else {
qWarning() << kMissingMetadata;
......@@ -104,8 +104,8 @@ void Fact::setRawValue(const QVariant& value)
_rawValue.setValue(typedValue);
_sendValueChangedSignal(cookedValue());
//-- Must be in this order
emit rawValueChanged(_rawValue);
emit _containerRawValueChanged(rawValue());
emit rawValueChanged(_rawValue);
}
}
} else {
......@@ -145,10 +145,12 @@ void Fact::setEnumIndex(int index)
void Fact::_containerSetRawValue(const QVariant& value)
{
_rawValue = value;
_sendValueChangedSignal(cookedValue());
emit vehicleUpdated(_rawValue);
emit rawValueChanged(_rawValue);
if(_rawValue != value) {
_rawValue = value;
_sendValueChangedSignal(cookedValue());
emit vehicleUpdated(_rawValue);
emit rawValueChanged(_rawValue);
}
}
QString Fact::name(void) const
......@@ -604,3 +606,13 @@ bool Fact::hasControl(void) const
return false;
}
}
bool Fact::readOnly(void) const
{
if (_metaData) {
return _metaData->readOnly();
} else {
qWarning() << kMissingMetadata;
return false;
}
}
......@@ -65,6 +65,7 @@ public:
Q_PROPERTY(bool typeIsString READ typeIsString CONSTANT)
Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT)
Q_PROPERTY(bool hasControl READ hasControl CONSTANT)
Q_PROPERTY(bool readOnly READ readOnly CONSTANT)
/// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well
......@@ -108,6 +109,7 @@ public:
bool typeIsString (void) const { return type() == FactMetaData::valueTypeString; }
bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; }
bool hasControl (void) const;
bool readOnly (void) const;
/// Returns the values as a string with full 18 digit precision if float/double.
QString rawValueStringFullPrecision(void) const;
......
......@@ -88,6 +88,7 @@ FactMetaData::FactMetaData(QObject* parent)
, _rebootRequired(false)
, _increment(std::numeric_limits<double>::quiet_NaN())
, _hasControl(true)
, _readOnly(false)
{
}
......@@ -108,6 +109,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
, _rebootRequired(false)
, _increment(std::numeric_limits<double>::quiet_NaN())
, _hasControl(true)
, _readOnly(false)
{
}
......@@ -135,6 +137,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
, _rebootRequired(false)
, _increment(std::numeric_limits<double>::quiet_NaN())
, _hasControl(true)
, _readOnly(false)
{
}
......@@ -164,7 +167,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_rebootRequired = other._rebootRequired;
_increment = other._increment;
_hasControl = other._hasControl;
_readOnly = other._readOnly;
return *this;
}
......
......@@ -98,6 +98,7 @@ public:
QString cookedUnits (void) const { return _cookedUnits; }
bool rebootRequired (void) const { return _rebootRequired; }
bool hasControl (void) const { return _hasControl; }
bool readOnly (void) const { return _readOnly; }
/// Amount to increment value when used in controls such as spin button or slider with detents.
/// NaN for no increment available.
......@@ -126,6 +127,7 @@ public:
void setRebootRequired (bool rebootRequired) { _rebootRequired = rebootRequired; }
void setIncrement (double increment) { _increment = increment; }
void setHasControl (bool bValue) { _hasControl = bValue; }
void setReadOnly (bool bValue) { _readOnly = bValue; }
void setTranslators(Translator rawTranslator, Translator cookedTranslator);
......@@ -221,6 +223,7 @@ private:
bool _rebootRequired;
double _increment;
bool _hasControl;
bool _readOnly;
// Exact conversion constants
static const struct UnitConsts_s {
......
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