Commit da5971a5 authored by Don Gagne's avatar Don Gagne

Better logging, plus some retry fixes

parent d1cc23a2
......@@ -32,7 +32,8 @@ typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;
QGC_LOGGING_CATEGORY(ParameterManagerVerboseLog, "ParameterManagerVerboseLog")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log")
Fact ParameterManager::_defaultFact;
......@@ -58,6 +59,7 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
, _prevWaitingReadParamNameCount(0)
, _prevWaitingWriteParamNameCount(0)
, _initialRequestRetryCount(0)
, _disableAllRetries(false)
, _totalParamCount(0)
{
_versionParam = vehicle->firmwarePlugin()->getVersionParam();
......@@ -69,21 +71,18 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
// We signal this to ouselves in order to start timer on our thread
connect(this, &ParameterManager::restartWaitingParamTimer, this, &ParameterManager::_restartWaitingParamTimer);
_initialRequestTimeoutTimer.setSingleShot(true);
_initialRequestTimeoutTimer.setInterval(6000);
_initialRequestTimeoutTimer.setInterval(20000);
connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
_waitingParamTimeoutTimer.setSingleShot(true);
_waitingParamTimeoutTimer.setInterval(1000);
_waitingParamTimeoutTimer.setInterval(3000);
connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterManager::_parameterUpdate);
_defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
qCDebug(ParameterManagerLog) << "Default component param" << _defaultComponentIdParam;
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Default component param" << _defaultComponentIdParam;
// Ensure the cache directory exists
QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
......@@ -103,28 +102,16 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
return;
}
_initialRequestTimeoutTimer.stop();
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
"_parameterUpdate" <<
"name:" << parameterName <<
"count:" << parameterCount <<
"index:" << parameterId <<
"mavType:" << mavType <<
"value:" << value <<
")";
if (_initialLoadComplete) {
qCDebug(ParameterManagerLog) << "_parameterUpdate (id:" << vehicleId <<
"componentId:" << componentId <<
"name:" << parameterName <<
"count:" << parameterCount <<
"index:" << parameterId <<
"mavType:" << mavType <<
"value:" << value <<
")";
} else {
// This is too noisy during initial load
qCDebug(ParameterManagerVerboseLog) << "_parameterUpdate (id:" << vehicleId <<
"componentId:" << componentId <<
"name:" << parameterName <<
"count:" << parameterCount <<
"index:" << parameterId <<
"mavType:" << mavType <<
"value:" << value <<
")";
}
_initialRequestTimeoutTimer.stop();
#if 0
// Handy for testing retry logic
......@@ -147,6 +134,14 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_tryCacheHashLoad(vehicleId, componentId, value);
return;
}
if (parameterId >= parameterCount) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Discarding bogus update name:id:count" << parameterName << parameterId << parameterCount;
return;
}
_initialRequestTimeoutTimer.stop();
_dataMutex.lock();
// Update our total parameter counts
......@@ -169,12 +164,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_waitingReadParamNameMap[componentId] = QMap<QString, int>();
_waitingWriteParamNameMap[componentId] = QMap<QString, int>();
qCDebug(ParameterManagerLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Seeing component for first time - paramcount:" << parameterCount;
}
// Determine default component id
if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
qCDebug(ParameterManagerLog) << "Default component id determined" << componentId;
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Default component id determined";
_defaultComponentId = componentId;
}
......@@ -189,16 +184,25 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_waitingWriteParamNameMap[componentId].contains(parameterName)) {
// We were waiting for this parameter, restart wait timer. Otherwise it is a spurious parameter update which
// means we should not reset the wait timer.
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer (valid param received)";
_waitingParamTimeoutTimer.start();
} else {
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName;
}
// Remove this parameter from the waiting lists
_waitingReadParamIndexMap[componentId].remove(parameterId);
_waitingReadParamNameMap[componentId].remove(parameterName);
_waitingWriteParamNameMap[componentId].remove(parameterName);
qCDebug(ParameterManagerVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
qCDebug(ParameterManagerLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
qCDebug(ParameterManagerLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];
if (_waitingReadParamIndexMap[componentId].count()) {
qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
}
if (_waitingReadParamNameMap[componentId].count()) {
qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
}
if (_waitingWriteParamNameMap[componentId].count()) {
qCDebug(ParameterManagerVerbose2Log) << _logVehiclePrefix(componentId) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];
}
// Track how many parameters we are still waiting for
......@@ -210,31 +214,31 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
}
if (waitingReadParamIndexCount) {
qCDebug(ParameterManagerLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
}
foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
}
if (waitingReadParamNameCount) {
qCDebug(ParameterManagerLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
}
foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
}
if (waitingWriteParamNameCount) {
qCDebug(ParameterManagerLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
}
int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
if (totalWaitingParamCount) {
qCDebug(ParameterManagerLog) << "totalWaitingParamCount:" << totalWaitingParamCount;
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "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.
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Stopping _waitingParamTimeoutTimer (all requests satisfied)";
_waitingParamTimeoutTimer.stop();
}
......@@ -255,7 +259,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
}
if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
qCDebug(ParameterManagerLog) << "Adding new fact";
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Adding new fact" << parameterName;
FactMetaData::ValueType_t factType;
switch (mavType) {
......@@ -339,6 +343,8 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
// Don't fail initial load complete if default component isn't found yet. That will be handled in wait timeout check.
_checkInitialLoadComplete(false /* failIfNoDefaultComponent */);
qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
}
/// Connected to Fact::valueUpdated
......@@ -363,14 +369,14 @@ void ParameterManager::_valueUpdated(const QVariant& value)
_dataMutex.unlock();
_writeParameterRaw(componentId, fact->name(), value);
qCDebug(ParameterManagerLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Set parameter - name:" << name << value << "(_waitingParamTimeoutTimer started)";
if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
qgcApp()->showMessage(QStringLiteral("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)
{
_dataMutex.lock();
......@@ -381,7 +387,7 @@ void ParameterManager::refreshAllParameters(uint8_t componentID)
// Reset index wait lists
foreach (int cid, _paramCountMap.keys()) {
// Add/Update all indices to the wait list, parameter index is 0-based
if(componentID != MAV_COMP_ID_ALL && componentID != cid)
if(componentId != MAV_COMP_ID_ALL && componentId != cid)
continue;
for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
// This will add a new waiting index if needed and set the retry count for that index to 0
......@@ -400,11 +406,11 @@ void ParameterManager::refreshAllParameters(uint8_t componentID)
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
componentID);
componentId);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
QString what = (componentID == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentID);
qCDebug(ParameterManagerLog) << "Request to refresh all parameters for component ID:" << what;
QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Request to refresh all parameters for component ID:" << what;
}
void ParameterManager::_determineDefaultComponentId(void)
......@@ -424,7 +430,7 @@ void ParameterManager::_determineDefaultComponentId(void)
}
if (_defaultComponentId == MAV_COMP_ID_ALL) {
qWarning() << "All parameters missing, unable to determine default componet id";
qWarning() << _logVehiclePrefix() << "All parameters missing, unable to determine default component id";
}
}
}
......@@ -435,7 +441,7 @@ int ParameterManager::_actualComponentId(int componentId)
if (componentId == FactSystem::defaultComponentId) {
componentId = _defaultComponentId;
if (componentId == FactSystem::defaultComponentId) {
qWarning() << "Default component id not set";
qWarning() << _logVehiclePrefix() << "Default component id not set";
}
}
......@@ -445,7 +451,7 @@ int ParameterManager::_actualComponentId(int componentId)
void ParameterManager::refreshParameter(int componentId, const QString& name)
{
componentId = _actualComponentId(componentId);
qCDebug(ParameterManagerLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << name << ")";
_dataMutex.lock();
......@@ -456,7 +462,8 @@ void ParameterManager::refreshParameter(int componentId, const QString& name)
_waitingReadParamNameMap[componentId].remove(mappedParamName); // Remove old wait entry if there
_waitingReadParamNameMap[componentId][mappedParamName] = 0; // Add new wait entry and update retry count
emit restartWaitingParamTimer();
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "restarting _waitingParamTimeout";
_waitingParamTimeoutTimer.start();
}
_dataMutex.unlock();
......@@ -467,7 +474,7 @@ void ParameterManager::refreshParameter(int componentId, const QString& name)
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
componentId = _actualComponentId(componentId);
qCDebug(ParameterManagerLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
if (name.startsWith(namePrefix)) {
......@@ -536,25 +543,32 @@ void ParameterManager::_waitingParamTimeout(void)
const int maxBatchSize = 10;
int batchCount = 0;
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout";
// First check for any missing parameters from the initial index based load
batchCount = 0;
foreach(int componentId, _waitingReadParamIndexMap.keys()) {
foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
if (_waitingReadParamIndexMap[componentId].count()) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
}
foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
if (++batchCount > maxBatchSize) {
goto Out;
}
_waitingReadParamIndexMap[componentId][paramIndex]++; // Bump retry count
if (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
if (_disableAllRetries || _waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
// Give up on this index
_failedReadParamIndexMap[componentId] << paramIndex;
qCDebug(ParameterManagerLog) << "Giving up on (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
_waitingReadParamIndexMap[componentId].remove(paramIndex);
} else {
// Retry again
paramsRequested = true;
_readParameterRaw(componentId, "", paramIndex);
qCDebug(ParameterManagerLog) << "Read re-request for (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
}
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
}
}
}
......@@ -562,6 +576,7 @@ void ParameterManager::_waitingParamTimeout(void)
if (!paramsRequested && _defaultComponentId == MAV_COMP_ID_ALL && !_waitingForDefaultComponent) {
// Initial load is complete but we still don't have default component params. Wait one more cycle to see if the
// default component finally shows up.
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component id";
_waitingParamTimeoutTimer.start();
_waitingForDefaultComponent = true;
return;
......@@ -578,14 +593,16 @@ void ParameterManager::_waitingParamTimeout(void)
_waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count
if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
qCDebug(ParameterManagerLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Write resend for (paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
}
} else {
// Exceeded max retry count, notify user
_waitingWriteParamNameMap[componentId].remove(paramName);
qgcApp()->showMessage(tr("Parameter write failed: comp:%1 param:%2").arg(componentId).arg(paramName));
QString errorMsg = tr("Parameter write failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
}
}
}
......@@ -598,14 +615,16 @@ void ParameterManager::_waitingParamTimeout(void)
_waitingReadParamNameMap[componentId][paramName]++; // Bump retry count
if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_readParameterRaw(componentId, paramName, -1);
qCDebug(ParameterManagerLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
}
} else {
// Exceeded max retry count, notify user
_waitingReadParamNameMap[componentId].remove(paramName);
qgcApp()->showMessage(tr("Parameter read failed: comp:%1 param:%2").arg(componentId).arg(paramName));
QString errorMsg = tr("Parameter read failed: veh:%1 comp:%2 param:%3").arg(_vehicle->id()).arg(componentId).arg(paramName);
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
}
}
}
......@@ -613,6 +632,7 @@ void ParameterManager::_waitingParamTimeout(void)
Out:
if (paramsRequested) {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - re-request";
_waitingParamTimeoutTimer.start();
}
}
......@@ -809,9 +829,9 @@ void ParameterManager::_saveToEEPROM(void)
0,
MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(ParameterManagerLog) << "_saveToEEPROM";
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM";
} else {
qCDebug(ParameterManagerLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
}
}
}
......@@ -941,11 +961,6 @@ FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE ma
}
}
void ParameterManager::_restartWaitingParamTimer(void)
{
_waitingParamTimeoutTimer.start();
}
void ParameterManager::_addMetaDataToDefaultComponent(void)
{
if (_defaultComponentId == MAV_COMP_ID_ALL) {
......@@ -1002,6 +1017,8 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete
_initialLoadComplete = true;
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete";
// Check for index based load failures
QString indexList;
bool initialLoadFailures = false;
......@@ -1012,29 +1029,33 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
}
indexList += QString("%1").arg(paramIndex);
initialLoadFailures = true;
qCDebug(ParameterManagerLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")";
qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
}
}
_missingParameters = false;
if (initialLoadFailures) {
_missingParameters = true;
qgcApp()->showMessage("QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
QString errorMsg = tr("QGroundControl was unable to retrieve the full set of parameters from vehicle %1. "
"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.");
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.").arg(_vehicle->id());
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterManagerLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
}
} else if (_defaultComponentId == FactSystem::defaultComponentId && !_defaultComponentIdParam.isEmpty()) {
// Missing default component when we should have one
_missingParameters = true;
qgcApp()->showMessage("QGroundControl did not receive parameters from the default component. "
QString errorMsg = tr("QGroundControl did not receive parameters from the default component for vehicle %1. "
"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.");
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.").arg(_vehicle->id());
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterManagerLog) << "Default component was never found, param:" << _defaultComponentIdParam;
qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "Default component was never found, param:" << _defaultComponentIdParam;
}
}
......@@ -1048,13 +1069,22 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
void ParameterManager::_initialRequestTimeout(void)
{
if (!_vehicle->genericFirmware()) {
// Generic vehicles (like BeBop) may not have any parameters, so don't annoy the user
qgcApp()->showMessage("Vehicle did not respond to request for parameters, retrying");
}
if (++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) {
if (!_vehicle->genericFirmware()) {
// Generic vehicles (like BeBop) may not have any parameters, so don't annoy the user
QString errorMsg = tr("Vehicle %1 did not respond to request for parameters, retrying").arg(_vehicle->id());
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
}
refreshAllParameters();
_initialRequestTimeoutTimer.start();
} else {
if (!_vehicle->genericFirmware()) {
// Generic vehicles (like BeBop) may not have any parameters, so don't annoy the user
QString errorMsg = tr("Vehicle %1 did not respond to request for parameters, failing after maximum number of retries").arg(_vehicle->id());
qCDebug(ParameterManagerLog) << errorMsg;
qgcApp()->showMessage(errorMsg);
}
}
}
......@@ -1444,3 +1474,11 @@ void ParameterManager::resetAllParametersToDefaults(void)
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
QString ParameterManager::_logVehiclePrefix(int componentId)
{
if (componentId == -1) {
return QString("V:%1").arg(_vehicle->id());
} else {
return QString("V:%1 C:%2").arg(_vehicle->id()).arg(componentId);
}
}
......@@ -28,7 +28,8 @@
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
/// Connects to Parameter Manager to load/update Facts
class ParameterManager : public QObject
......@@ -123,9 +124,6 @@ signals:
/// Signalled to update progress of full parameter list request
void parameterListProgress(float value);
/// Signalled to ourselves in order to get call on our own thread
void restartWaitingParamTimer(void);
protected:
Vehicle* _vehicle;
......@@ -133,7 +131,6 @@ protected:
void _parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
void _valueUpdated(const QVariant& value);
void _restartWaitingParamTimer(void);
void _waitingParamTimeout(void);
void _tryCacheLookup(void);
void _initialRequestTimeout(void);
......@@ -150,6 +147,7 @@ private:
void _addMetaDataToDefaultComponent(void);
QString _remapParamNameToVersion(const QString& paramName);
void _loadOfflineEditingParams(void);
QString _logVehiclePrefix(int componentId = -1);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
......@@ -183,10 +181,11 @@ private:
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
static const int _maxInitialRequestListRetry = 4; ///< Maximum retries for request list
int _initialRequestRetryCount; ///< Current retry count for request list
static const int _maxInitialLoadRetrySingleParam = 5; ///< Maximum retries for initial index based load of a single param
static const int _maxReadWriteRetry = 5; ///< Maximum retries read/write
bool _disableAllRetries; ///< true: Don't retry any requests (used for testing)
QMap<int, int> _paramCountMap; ///< Key: Component id, Value: count of parameters in this component
QMap<int, QMap<int, int> > _waitingReadParamIndexMap; ///< Key: Component id, Value: Map { Key: parameter index still waiting for, Value: retry count }
......
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