Commit ca438f88 authored by Don Gagne's avatar Don Gagne

Performance fixes

- Cache only supported on PX4. Solo sends param updates at a high rate
to update gimbal values. This was causing the cache to update itself at
too high of a rate, killing performance, especially on iOS.
- Fixed read/write index usage to provide correct progress bar updates
parent 8af16687
......@@ -47,6 +47,9 @@ ParameterLoader::ParameterLoader(Vehicle* vehicle)
, _defaultComponentId(MAV_COMP_ID_ALL)
, _parameterSetMajorVersion(-1)
, _parameterMetaData(NULL)
, _prevWaitingReadParamIndexCount(0)
, _prevWaitingReadParamNameCount(0)
, _prevWaitingWriteParamNameCount(0)
, _initialRequestRetryCount(0)
, _totalParamCount(0)
{
......@@ -90,14 +93,26 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
_initialRequestTimeoutTimer.stop();
qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId <<
"componentId:" << componentId <<
"name:" << parameterName <<
"count:" << parameterCount <<
"index:" << parameterId <<
"mavType:" << mavType <<
"value:" << value <<
")";
if (_initialLoadComplete) {
qCDebug(ParameterLoaderLog) << "_parameterUpdate (id:" << uasId <<
"componentId:" << componentId <<
"name:" << parameterName <<
"count:" << parameterCount <<
"index:" << parameterId <<
"mavType:" << mavType <<
"value:" << value <<
")";
} else {
// This is too noisy during initial load
qCDebug(ParameterLoaderVerboseLog) << "_parameterUpdate (id:" << uasId <<
"componentId:" << componentId <<
"name:" << parameterName <<
"count:" << parameterCount <<
"index:" << parameterId <<
"mavType:" << mavType <<
"value:" << value <<
")";
}
#if 0
// Handy for testing retry logic
......@@ -115,7 +130,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
}
#endif
if (parameterName == "_HASH_CHECK") {
if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
/* we received a cache hash, potentially load from cache */
_tryCacheHashLoad(uasId, componentId, value);
return;
......@@ -201,20 +216,25 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
}
int waitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount + waitingWriteParamNameCount;
if (waitingParamCount) {
qCDebug(ParameterLoaderLog) << "waitingParamCount:" << waitingParamCount;
int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
if (totalWaitingParamCount) {
qCDebug(ParameterLoaderLog) << "totalWaitingParamCount:" << totalWaitingParamCount;
} else if (_defaultComponentId != MAV_COMP_ID_ALL) {
// No more parameters to wait for, stop the timeout. Be careful to not stop timer if we don't have the default
// component yet.
_waitingParamTimeoutTimer.stop();
}
// Update progress bar
if (waitingParamCount == 0) {
emit parameterListProgress(0);
// Update progress bar for waiting reads
if (readWaitingParamCount == 0) {
// We are no longer waiting for any reads to complete
if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0) {
// Set progress to 0 if not already there
emit parameterListProgress(0);
}
} else {
emit parameterListProgress((float)(_totalParamCount - waitingParamCount) / (float)_totalParamCount);
emit parameterListProgress((float)(_totalParamCount - readWaitingParamCount) / (float)_totalParamCount);
}
// Get parameter set version
......@@ -286,12 +306,25 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
_setupGroupMap();
}
if (waitingParamCount == 0) {
// Now that we know vehicle is up to date persist
if (_prevWaitingWriteParamNameCount != 0 && waitingWriteParamNameCount == 0) {
// If all the writes just finished the vehicle is up to date, so persist.
_saveToEEPROM();
_writeLocalParamCache(uasId, componentId);
}
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
// which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
// which in turn causes a perf problem with all the param cache updates.
if (_vehicle->px4Firmware()) {
if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
// All reads just finished, update the cache
_writeLocalParamCache(uasId, componentId);
}
}
_prevWaitingReadParamIndexCount = waitingReadParamIndexCount;
_prevWaitingReadParamNameCount = waitingReadParamNameCount;
_prevWaitingWriteParamNameCount = waitingWriteParamNameCount;
// Don't fail initial load complete if default component isn't found yet. That will be handled in wait timeout check.
_checkInitialLoadComplete(false /* failIfNoDefaultComponent */);
}
......@@ -955,8 +988,10 @@ void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
"This will cause QGroundControl to be unable to display its full user interface. "
"If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.");
qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
emit parametersReady(true);
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
}
emit parametersReady(true /* missingParameters */);
return;
}
......@@ -966,15 +1001,17 @@ void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
"This will cause QGroundControl to be unable to display its full user interface. "
"If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.");
qCWarning(ParameterLoaderLog) << "Default component was never found, param:" << _defaultComponentIdParam;
emit parametersReady(true);
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterLoaderLog) << "Default component was never found, param:" << _defaultComponentIdParam;
}
emit parametersReady(true /* missingParameters */);
return;
}
// No failures, signal good load
_parametersReady = true;
_determineDefaultComponentId();
emit parametersReady(false);
emit parametersReady(false /* no missingParameters */);
}
void ParameterLoader::_initialRequestTimeout(void)
......
......@@ -151,7 +151,13 @@ private:
int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known
QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
static const int _maxInitialRequestListRetry = 5; ///< Maximum retries for request list
// Wait counts from previous parameter update cycle
int _prevWaitingReadParamIndexCount;
int _prevWaitingReadParamNameCount;
int _prevWaitingWriteParamNameCount;
static const int _maxInitialRequestListRetry = 4; ///< Maximum retries for request list
int _initialRequestRetryCount; ///< Current retry count for request list
static const int _maxInitialLoadRetrySingleParam = 10; ///< Maximum retries for initial index based load of a single param
static const int _maxReadWriteRetry = 5; ///< Maximum retries read/write
......
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