Browse Source

Instead of resetting all parameters when some parameter change, explicitly define list of parameters that must be requested when a given parameter change.

QGC4.4
Gus Grubba 8 years ago
parent
commit
d9baef94d5
  1. 131
      src/Camera/QGCCameraControl.cc
  2. 6
      src/Camera/QGCCameraControl.h
  3. 18
      src/Camera/QGCCameraIO.cc
  4. 1
      src/Camera/QGCCameraIO.h

131
src/Camera/QGCCameraControl.cc

@ -19,33 +19,34 @@
QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog") QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog")
QGC_LOGGING_CATEGORY(CameraControlLogVerbose, "CameraControlLogVerbose") QGC_LOGGING_CATEGORY(CameraControlLogVerbose, "CameraControlLogVerbose")
static const char* kDefnition = "definition"; static const char* kCondition = "condition";
static const char* kParameters = "parameters";
static const char* kParameter = "parameter";
static const char* kVersion = "version";
static const char* kModel = "model";
static const char* kVendor = "vendor";
static const char* kLocalization = "localization";
static const char* kLocale = "locale";
static const char* kStrings = "strings";
static const char* kName = "name";
static const char* kValue = "value";
static const char* kControl = "control"; 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";
static const char* kDefault = "default"; static const char* kDefault = "default";
static const char* kDefnition = "definition";
static const char* kDescription = "description"; static const char* kDescription = "description";
static const char* kExclusions = "exclusions";
static const char* kExclusion = "exclude"; static const char* kExclusion = "exclude";
static const char* kRoption = "roption"; static const char* kExclusions = "exclusions";
static const char* kCondition = "condition"; static const char* kLocale = "locale";
static const char* kParameterranges = "parameterranges"; static const char* kLocalization = "localization";
static const char* kParameterrange = "parameterrange"; static const char* kModel = "model";
static const char* kName = "name";
static const char* kOption = "option";
static const char* kOptions = "options";
static const char* kOriginal = "original"; static const char* kOriginal = "original";
static const char* kParameter = "parameter";
static const char* kParameterrange = "parameterrange";
static const char* kParameterranges = "parameterranges";
static const char* kParameters = "parameters";
static const char* kReadOnly = "readonly";
static const char* kRoption = "roption";
static const char* kStrings = "strings";
static const char* kTranslated = "translated"; static const char* kTranslated = "translated";
static const char* kReset = "reset"; static const char* kType = "type";
static const char* kUpdate = "update";
static const char* kUpdates = "updates";
static const char* kValue = "value";
static const char* kVendor = "vendor";
static const char* kVersion = "version";
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
static bool static bool
@ -164,8 +165,6 @@ QGCCameraControl::_initWhenReady()
} }
connect(_vehicle, &Vehicle::mavCommandResult, this, &QGCCameraControl::_mavCommandResult); connect(_vehicle, &Vehicle::mavCommandResult, this, &QGCCameraControl::_mavCommandResult);
connect(&_captureStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_requestCaptureStatus); connect(&_captureStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_requestCaptureStatus);
connect(&_updateTimer, &QTimer::timeout, this, &QGCCameraControl::_updateTimeout);
_updateTimer.setSingleShot(true);
_captureStatusTimer.setSingleShot(true); _captureStatusTimer.setSingleShot(true);
QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo); QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo);
_captureStatusTimer.start(2750); _captureStatusTimer.start(2750);
@ -574,11 +573,11 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
qCritical() << QString("Parameter %1 missing parameter description").arg(factName); qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
return false; return false;
} }
//-- Does it require full update on changes? //-- Check for updates
bool update = false; QStringList updates = _loadUpdates(parameterNode);
read_attribute(parameterNode, kReset, update); if(updates.size()) {
if(update) { qCDebug(CameraControlLogVerbose) << "Parameter" << factName << "requires updates for:" << updates;
_requestUpdates << factName; _requestUpdates[factName] = updates;
} }
//-- Build metadata //-- Build metadata
FactMetaData* metaData = new FactMetaData(factType, factName, this); FactMetaData* metaData = new FactMetaData(factType, factName, this);
@ -925,6 +924,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
QMap<Fact*, QString> rangesReset; QMap<Fact*, QString> rangesReset;
QStringList changedList; QStringList changedList;
QStringList resetList; QStringList resetList;
QStringList updates;
//-- Iterate range sets looking for limited ranges //-- Iterate range sets looking for limited ranges
foreach(QGCCameraOptionRange* pRange, _optionRanges) { foreach(QGCCameraOptionRange* pRange, _optionRanges) {
//-- If this fact or one of its conditions is part of this range set //-- If this fact or one of its conditions is part of this range set
@ -940,7 +940,6 @@ QGCCameraControl::_updateRanges(Fact* pFact)
if(pTFact->enumStrings() != pRange->optNames) { if(pTFact->enumStrings() != pRange->optNames) {
//-- Set limited range set //-- Set limited range set
rangesSet[pTFact] = pRange; rangesSet[pTFact] = pRange;
qCDebug(CameraControlLogVerbose) << "Limited set of options for:" << pRange->targetParam << pRange->optNames;
} }
changedList << pRange->targetParam; changedList << pRange->targetParam;
} }
@ -955,51 +954,39 @@ QGCCameraControl::_updateRanges(Fact* pFact)
if(pTFact->enumStrings() != _originalOptNames[pRange->targetParam]) { if(pTFact->enumStrings() != _originalOptNames[pRange->targetParam]) {
//-- Restore full option set //-- Restore full option set
rangesReset[pTFact] = pRange->targetParam; rangesReset[pTFact] = pRange->targetParam;
qCDebug(CameraControlLogVerbose) << "Restore full set of options for:" << pRange->targetParam << _originalOptNames[pRange->targetParam];
} }
resetList << pRange->targetParam; resetList << pRange->targetParam;
} }
} }
} }
//-- Update limited range set //-- Update limited range set
foreach (Fact* pFact, rangesSet.keys()) { foreach (Fact* f, rangesSet.keys()) {
pFact->setEnumInfo(rangesSet[pFact]->optNames, rangesSet[pFact]->optVariants); f->setEnumInfo(rangesSet[f]->optNames, rangesSet[f]->optVariants);
if(!_updates.contains(pFact)) { if(!updates.contains(f->name())) {
_paramIO[pFact->name()]->optNames = rangesSet[pFact]->optNames; _paramIO[f->name()]->optNames = rangesSet[f]->optNames;
_paramIO[pFact->name()]->optVariants = rangesSet[pFact]->optVariants; _paramIO[f->name()]->optVariants = rangesSet[f]->optVariants;
_updates << pFact; emit f->enumsChanged();
qCDebug(CameraControlLogVerbose) << "Limited set of options for:" << f->name() << rangesSet[f]->optNames;;
updates << f->name();
} }
} }
//-- Restore full range set //-- Restore full range set
foreach (Fact* pFact, rangesReset.keys()) { foreach (Fact* f, rangesReset.keys()) {
pFact->setEnumInfo(_originalOptNames[rangesReset[pFact]], _originalOptValues[rangesReset[pFact]]); f->setEnumInfo(_originalOptNames[rangesReset[f]], _originalOptValues[rangesReset[f]]);
if(!_updates.contains(pFact)) { if(!updates.contains(f->name())) {
_paramIO[pFact->name()]->optNames = _originalOptNames[rangesReset[pFact]]; _paramIO[f->name()]->optNames = _originalOptNames[rangesReset[f]];
_paramIO[pFact->name()]->optVariants = _originalOptValues[rangesReset[pFact]]; _paramIO[f->name()]->optVariants = _originalOptValues[rangesReset[f]];
_updates << pFact; emit f->enumsChanged();
qCDebug(CameraControlLogVerbose) << "Restore full set of options for:" << f->name() << _originalOptNames[f->name()];
updates << f->name();
} }
} }
//-- Parameter update requests //-- Parameter update requests
if(_requestUpdates.contains(pFact->name())) { if(_requestUpdates.contains(pFact->name())) {
QTimer::singleShot(250, this, &QGCCameraControl::_requestAllParameters); foreach(QString param, _requestUpdates[pFact->name()]) {
} _paramIO[param]->paramRequest();
//-- Update UI (Asynchronous state where values come back after a while) }
if(_updates.size()) {
_updateTimer.start(500);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_updateTimeout()
{
//-- Update UI
foreach (Fact* pFact, _updates) {
pFact->setEnumInfo(_paramIO[pFact->name()]->optNames, _paramIO[pFact->name()]->optVariants);
qCDebug(CameraControlLogVerbose) << "Update enums" << pFact->name() << pFact->enumStrings();
emit pFact->enumsChanged();
} }
_updates.clear();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -1082,7 +1069,7 @@ QGCCameraControl::_loadExclusions(QDomNode option)
QDomElement optionElem = option.toElement(); QDomElement optionElem = option.toElement();
QDomNodeList excRoot = optionElem.elementsByTagName(kExclusions); QDomNodeList excRoot = optionElem.elementsByTagName(kExclusions);
if(excRoot.size()) { if(excRoot.size()) {
//-- Iterate options //-- Iterate exclusions
QDomNode node = excRoot.item(0); QDomNode node = excRoot.item(0);
QDomElement elem = node.toElement(); QDomElement elem = node.toElement();
QDomNodeList exclusions = elem.elementsByTagName(kExclusion); QDomNodeList exclusions = elem.elementsByTagName(kExclusion);
@ -1097,6 +1084,28 @@ QGCCameraControl::_loadExclusions(QDomNode option)
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadUpdates(QDomNode option)
{
QStringList updateList;
QDomElement optionElem = option.toElement();
QDomNodeList updateRoot = optionElem.elementsByTagName(kUpdates);
if(updateRoot.size()) {
//-- Iterate updates
QDomNode node = updateRoot.item(0);
QDomElement elem = node.toElement();
QDomNodeList updates = elem.elementsByTagName(kUpdate);
for(int i = 0; i < updates.size(); i++) {
QString update = updates.item(i).toElement().text();
if(!update.isEmpty()) {
updateList << update;
}
}
}
return updateList;
}
//-----------------------------------------------------------------------------
bool bool
QGCCameraControl::_loadRanges(QDomNode option, const QString factName, QString paramValue) QGCCameraControl::_loadRanges(QDomNode option, const QString factName, QString paramValue)
{ {

6
src/Camera/QGCCameraControl.h

@ -172,7 +172,6 @@ private slots:
void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle); void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
void _dataReady (QByteArray data); void _dataReady (QByteArray data);
void _paramDone (); void _paramDone ();
void _updateTimeout ();
private: private:
bool _handleLocalization (QByteArray& bytes); bool _handleLocalization (QByteArray& bytes);
@ -191,6 +190,7 @@ private:
void _handleDefinitionFile (const QString& url); void _handleDefinitionFile (const QString& url);
QStringList _loadExclusions (QDomNode option); QStringList _loadExclusions (QDomNode option);
QStringList _loadUpdates (QDomNode option);
QString _getParamName (const char* param_id); QString _getParamName (const char* param_id);
protected: protected:
@ -210,15 +210,13 @@ protected:
QStringList _activeSettings; QStringList _activeSettings;
QStringList _settings; QStringList _settings;
QTimer _captureStatusTimer; QTimer _captureStatusTimer;
QTimer _updateTimer;
QList<QGCCameraOptionExclusion*> _valueExclusions; QList<QGCCameraOptionExclusion*> _valueExclusions;
QList<QGCCameraOptionRange*> _optionRanges; QList<QGCCameraOptionRange*> _optionRanges;
QMap<QString, QStringList> _originalOptNames; QMap<QString, QStringList> _originalOptNames;
QMap<QString, QVariantList> _originalOptValues; QMap<QString, QVariantList> _originalOptValues;
QMap<QString, QGCCameraParamIO*> _paramIO; QMap<QString, QGCCameraParamIO*> _paramIO;
QVector<Fact*> _updates;
int _storageInfoRetries; int _storageInfoRetries;
int _captureInfoRetries; int _captureInfoRetries;
//-- Parameters that require a full update //-- Parameters that require a full update
QStringList _requestUpdates; QMap<QString, QStringList> _requestUpdates;
}; };

18
src/Camera/QGCCameraIO.cc

@ -21,6 +21,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
, _requestRetries(0) , _requestRetries(0)
, _done(false) , _done(false)
, _updateOnSet(false) , _updateOnSet(false)
, _forceUIUpdate(false)
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
_paramWriteTimer.setSingleShot(true); _paramWriteTimer.setSingleShot(true);
@ -75,10 +76,12 @@ QGCCameraParamIO::setParamRequest()
void void
QGCCameraParamIO::_factChanged(QVariant value) QGCCameraParamIO::_factChanged(QVariant value)
{ {
Q_UNUSED(value); if(!_forceUIUpdate) {
qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed to" << value; Q_UNUSED(value);
//-- TODO: Do we really want to update the UI now or only when we receive the ACK? qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed to" << value;
_control->factChanged(_fact); //-- TODO: Do we really want to update the UI now or only when we receive the ACK?
_control->factChanged(_fact);
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -216,6 +219,11 @@ QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value)
_fact->_containerSetRawValue(newValue); _fact->_containerSetRawValue(newValue);
} }
_paramRequestReceived = true; _paramRequestReceived = true;
if(_forceUIUpdate) {
emit _fact->rawValueChanged(_fact->rawValue());
emit _fact->valueChanged(_fact->rawValue());
_forceUIUpdate = false;
}
if(!_done) { if(!_done) {
_done = true; _done = true;
_control->_paramDone(); _control->_paramDone();
@ -285,7 +293,9 @@ QGCCameraParamIO::paramRequest(bool reset)
{ {
if(reset) { if(reset) {
_requestRetries = 0; _requestRetries = 0;
_forceUIUpdate = true;
} }
qCDebug(CameraIOLog) << "Request parameter:" << _fact->name();
char param_id[MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN + 1]; char param_id[MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
memset(param_id, 0, sizeof(param_id)); memset(param_id, 0, sizeof(param_id));
strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN); strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN);

1
src/Camera/QGCCameraIO.h

@ -54,5 +54,6 @@ private:
bool _updateOnSet; bool _updateOnSet;
MAV_PARAM_TYPE _mavParamType; MAV_PARAM_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink; MAVLinkProtocol* _pMavlink;
bool _forceUIUpdate;
}; };

Loading…
Cancel
Save