Browse Source

Fix broken hash check with param load

QGC4.4
DonLakeFlyer 8 years ago
parent
commit
bcffae2b13
  1. 2
      src/FactSystem/ParameterManager.cc

2
src/FactSystem/ParameterManager.cc

@ -110,7 +110,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString @@ -110,7 +110,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
// ArduPilot has this strange behavior of streaming parameters that we didn't ask for. This even happens before it responds to the
// PARAM_REQUEST_LIST. We disregard any of this until the initial request is responded to.
if (parameterId == 65535 && _initialRequestTimeoutTimer.isActive()) {
if (parameterId == 65535 && parameterName != "_HASH_CHECK" && _initialRequestTimeoutTimer.isActive()) {
qCDebug(ParameterManagerVerbose1Log) << "Disregarding unrequested param prior to intial list response" << parameterName;
return;
}

Loading…
Cancel
Save