ParameterManager.cc 57.7 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

10 11 12 13

/// @file
///     @author Don Gagne <don@thegagnes.com>

14
#include "ParameterManager.h"
15 16
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
17
#include "QGCApplication.h"
18
#include "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
19
#include "FirmwarePlugin.h"
Don Gagne's avatar
Don Gagne committed
20
#include "APMFirmwarePlugin.h"
21
#include "UAS.h"
22
#include "JsonHelper.h"
23

24
#include <QEasingCurve>
25 26
#include <QFile>
#include <QDebug>
27
#include <QVariantAnimation>
28
#include <QJsonArray>
29

30 31 32 33 34
/* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;

35
QGC_LOGGING_CATEGORY(ParameterManagerVerboseLog, "ParameterManagerVerboseLog")
36

37
Fact ParameterManager::_defaultFact;
Don Gagne's avatar
Don Gagne committed
38

39 40 41 42 43
const char* ParameterManager::_cachedMetaDataFilePrefix =   "ParameterFactMetaData";
const char* ParameterManager::_jsonParametersKey =          "parameters";
const char* ParameterManager::_jsonCompIdKey =              "compId";
const char* ParameterManager::_jsonParamNameKey =           "name";
const char* ParameterManager::_jsonParamValueKey =          "value";
44

45
ParameterManager::ParameterManager(Vehicle* vehicle)
46
    : QObject(vehicle)
47
    , _vehicle(vehicle)
48
    , _mavlink(NULL)
49
    , _parametersReady(false)
50
    , _missingParameters(false)
51
    , _initialLoadComplete(false)
52
    , _waitingForDefaultComponent(false)
53
    , _saveRequired(false)
54
    , _defaultComponentId(MAV_COMP_ID_ALL)
55 56
    , _parameterSetMajorVersion(-1)
    , _parameterMetaData(NULL)
Don Gagne's avatar
Don Gagne committed
57 58 59
    , _prevWaitingReadParamIndexCount(0)
    , _prevWaitingReadParamNameCount(0)
    , _prevWaitingWriteParamNameCount(0)
60
    , _initialRequestRetryCount(0)
61
    , _totalParamCount(0)
62
{
63 64
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();

65 66 67 68 69 70
    if (_vehicle->isOfflineEditingVehicle()) {
        _loadOfflineEditingParams();
        return;
    }

    _mavlink = qgcApp()->toolbox()->mavlinkProtocol();
dogmaphobic's avatar
dogmaphobic committed
71

72
    // We signal this to ouselves in order to start timer on our thread
73
    connect(this, &ParameterManager::restartWaitingParamTimer, this, &ParameterManager::_restartWaitingParamTimer);
dogmaphobic's avatar
dogmaphobic committed
74

75 76
    _initialRequestTimeoutTimer.setSingleShot(true);
    _initialRequestTimeoutTimer.setInterval(6000);
77
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
78

79
    _waitingParamTimeoutTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
80
    _waitingParamTimeoutTimer.setInterval(1000);
81
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
82

83
    connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterManager::_parameterUpdate);
84

85
    _defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
86
    qCDebug(ParameterManagerLog) << "Default component param" << _defaultComponentIdParam;
87

88 89 90
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
    refreshAllParameters();
91 92
}

93
ParameterManager::~ParameterManager()
94
{
95
    delete _parameterMetaData;
96 97 98
}

/// Called whenever a parameter is updated or first seen.
99
void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
100 101
{
    // Is this for our uas?
102
    if (vehicleId != _vehicle->id()) {
103 104
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
105

106 107
    _initialRequestTimeoutTimer.stop();

Don Gagne's avatar
Don Gagne committed
108
    if (_initialLoadComplete) {
109
        qCDebug(ParameterManagerLog) << "_parameterUpdate (id:" << vehicleId <<
Don Gagne's avatar
Don Gagne committed
110 111 112 113 114 115 116 117 118
                                        "componentId:" << componentId <<
                                        "name:" << parameterName <<
                                        "count:" << parameterCount <<
                                        "index:" << parameterId <<
                                        "mavType:" << mavType <<
                                        "value:" << value <<
                                        ")";
    } else {
        // This is too noisy during initial load
119
        qCDebug(ParameterManagerVerboseLog) << "_parameterUpdate (id:" << vehicleId <<
Don Gagne's avatar
Don Gagne committed
120 121 122 123 124 125 126 127
                                       "componentId:" << componentId <<
                                       "name:" << parameterName <<
                                       "count:" << parameterCount <<
                                       "index:" << parameterId <<
                                       "mavType:" << mavType <<
                                       "value:" << value <<
                                       ")";
    }
dogmaphobic's avatar
dogmaphobic committed
128

129 130 131
#if 0
    // Handy for testing retry logic
    static int counter = 0;
132
    if (counter++ & 0x8) {
133
        qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
134 135 136
        return;
    }
#endif
137

138 139 140 141 142 143 144
#if 0
    // Use this to test missing default component id
    if (componentId == 50) {
        return;
    }
#endif

Don Gagne's avatar
Don Gagne committed
145
    if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
146
        /* we received a cache hash, potentially load from cache */
147
        _tryCacheHashLoad(vehicleId, componentId, value);
148 149
        return;
    }
150
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
151

152 153 154 155 156
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
157 158

    _mapParameterId2Name[componentId][parameterId] = parameterName;
dogmaphobic's avatar
dogmaphobic committed
159

160 161
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
162 163 164 165
        // Add all indices to the wait list, parameter index is 0-based
        for (int waitingIndex=0; waitingIndex<parameterCount; waitingIndex++) {
            // This will add the new component id, as well as the the new waiting index and set the retry count for that index to 0
            _waitingReadParamIndexMap[componentId][waitingIndex] = 0;
166
        }
dogmaphobic's avatar
dogmaphobic committed
167

168 169 170
        // The read and write waiting lists for this component are initialized the empty
        _waitingReadParamNameMap[componentId] = QMap<QString, int>();
        _waitingWriteParamNameMap[componentId] = QMap<QString, int>();
dogmaphobic's avatar
dogmaphobic committed
171

172
        qCDebug(ParameterManagerLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
173
    }
dogmaphobic's avatar
dogmaphobic committed
174

175 176
    // Determine default component id
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
177
        qCDebug(ParameterManagerLog) << "Default component id determined" << componentId;
178 179 180 181 182 183 184 185 186
        _defaultComponentId = componentId;
    }

    bool componentParamsComplete = false;
    if (_waitingReadParamIndexMap[componentId].count() == 1) {
        // We need to know when we get the last param from a component in order to complete setup
        componentParamsComplete = true;
    }

187 188 189 190 191 192 193 194
    if (_waitingReadParamIndexMap[componentId].contains(parameterId) ||
        _waitingReadParamNameMap[componentId].contains(parameterName) ||
        _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.
        _waitingParamTimeoutTimer.start();
    }

195
    // Remove this parameter from the waiting lists
196 197 198
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
199 200 201
    qCDebug(ParameterManagerVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
    qCDebug(ParameterManagerLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterManagerLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];
202 203

    // Track how many parameters we are still waiting for
dogmaphobic's avatar
dogmaphobic committed
204

205 206 207
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
208

209 210 211 212
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
213
        qCDebug(ParameterManagerLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
214 215
    }

dogmaphobic's avatar
dogmaphobic committed
216

217 218 219 220
    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
221
        qCDebug(ParameterManagerLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
222
    }
dogmaphobic's avatar
dogmaphobic committed
223

224 225 226 227
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
228
        qCDebug(ParameterManagerLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
229
    }
dogmaphobic's avatar
dogmaphobic committed
230

Don Gagne's avatar
Don Gagne committed
231 232 233
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
234
        qCDebug(ParameterManagerLog) << "totalWaitingParamCount:" << totalWaitingParamCount;
235
    } else if (_defaultComponentId != MAV_COMP_ID_ALL) {
236 237
        // No more parameters to wait for, stop the timeout. Be careful to not stop timer if we don't have the default
        // component yet.
238 239 240
        _waitingParamTimeoutTimer.stop();
    }

Don Gagne's avatar
Don Gagne committed
241 242 243 244 245 246 247
    // 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);
        }
248
    } else {
Don Gagne's avatar
Don Gagne committed
249
        emit parameterListProgress((float)(_totalParamCount - readWaitingParamCount) / (float)_totalParamCount);
250
    }
dogmaphobic's avatar
dogmaphobic committed
251

252 253 254 255 256
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

257
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
258
        qCDebug(ParameterManagerLog) << "Adding new fact";
dogmaphobic's avatar
dogmaphobic committed
259

260 261 262 263 264 265
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
266
                factType = FactMetaData::valueTypeInt8;
267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290
                break;
            case MAV_PARAM_TYPE_UINT16:
                factType = FactMetaData::valueTypeUint16;
                break;
            case MAV_PARAM_TYPE_INT16:
                factType = FactMetaData::valueTypeInt16;
                break;
            case MAV_PARAM_TYPE_UINT32:
                factType = FactMetaData::valueTypeUint32;
                break;
            case MAV_PARAM_TYPE_INT32:
                factType = FactMetaData::valueTypeInt32;
                break;
            case MAV_PARAM_TYPE_REAL32:
                factType = FactMetaData::valueTypeFloat;
                break;
            case MAV_PARAM_TYPE_REAL64:
                factType = FactMetaData::valueTypeDouble;
                break;
            default:
                factType = FactMetaData::valueTypeInt32;
                qCritical() << "Unsupported fact type" << mavType;
                break;
        }
dogmaphobic's avatar
dogmaphobic committed
291

292
        Fact* fact = new Fact(componentId, parameterName, factType, this);
dogmaphobic's avatar
dogmaphobic committed
293

294
        _mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact);
dogmaphobic's avatar
dogmaphobic committed
295

296
        // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
297
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterManager::_valueUpdated);
298
    }
dogmaphobic's avatar
dogmaphobic committed
299

Don Gagne's avatar
Don Gagne committed
300 301
    _dataMutex.unlock();

302
    Q_ASSERT(_mapParameterName2Variant[componentId].contains(parameterName));
dogmaphobic's avatar
dogmaphobic committed
303

304 305
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
306
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
307

308 309 310 311 312 313 314 315 316 317 318 319 320
    if (componentParamsComplete) {
        if (componentId == _defaultComponentId) {
            // Add meta data to default component. We need to do this before we setup the group map since group
            // map requires meta data.
            _addMetaDataToDefaultComponent();
        }

        // When we are getting the very last component param index, reset the group maps to update for the
        // new params. By handling this here, we can pick up components which finish up later than the default
        // component param set.
        _setupGroupMap();
    }

Don Gagne's avatar
Don Gagne committed
321 322
    if (_prevWaitingWriteParamNameCount != 0 &&  waitingWriteParamNameCount == 0) {
        // If all the writes just finished the vehicle is up to date, so persist.
323 324
        _saveToEEPROM();
    }
dogmaphobic's avatar
dogmaphobic committed
325

Don Gagne's avatar
Don Gagne committed
326 327 328 329 330 331
    // 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
332
            _writeLocalParamCache(vehicleId, componentId);
Don Gagne's avatar
Don Gagne committed
333 334 335 336 337 338 339
        }
    }

    _prevWaitingReadParamIndexCount = waitingReadParamIndexCount;
    _prevWaitingReadParamNameCount = waitingReadParamNameCount;
    _prevWaitingWriteParamNameCount = waitingWriteParamNameCount;

340 341
    // Don't fail initial load complete if default component isn't found yet. That will be handled in wait timeout check.
    _checkInitialLoadComplete(false /* failIfNoDefaultComponent */);
342 343 344 345
}

/// Connected to Fact::valueUpdated
///
346
/// Writes the parameter to mavlink, sets up for write wait
347
void ParameterManager::_valueUpdated(const QVariant& value)
348 349 350
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
351

352
    int componentId = fact->componentId();
353
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
354

355
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
356

357
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
358 359
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
360
    _waitingParamTimeoutTimer.start();
361
    _saveRequired = true;
dogmaphobic's avatar
dogmaphobic committed
362

363
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
364

365
    _writeParameterRaw(componentId, fact->name(), value);
366
    qCDebug(ParameterManagerLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
367

368 369
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
        qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
370
    }
371 372
}

373
void ParameterManager::refreshAllParameters(uint8_t componentID)
374
{
375
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
376

377 378 379 380
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

381
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
382
    foreach (int cid, _paramCountMap.keys()) {
383
        // Add/Update all indices to the wait list, parameter index is 0-based
dogmaphobic's avatar
dogmaphobic committed
384 385 386
        if(componentID != MAV_COMP_ID_ALL && componentID != cid)
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
387
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
388
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
389 390
        }
    }
dogmaphobic's avatar
dogmaphobic committed
391

392
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
393

394
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
395
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
396

397
    mavlink_message_t msg;
dogmaphobic's avatar
dogmaphobic committed
398
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), componentID);
399
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
400

dogmaphobic's avatar
dogmaphobic committed
401
    QString what = (componentID == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentID);
402
    qCDebug(ParameterManagerLog) << "Request to refresh all parameters for component ID:" << what;
403 404
}

405
void ParameterManager::_determineDefaultComponentId(void)
406
{
407
    if (_defaultComponentId == MAV_COMP_ID_ALL) {
408 409 410
        // We don't have a default component id yet. That means the plugin can't provide
        // the param to trigger off of. Instead we use the most prominent component id in
        // the set of parameters. Better than nothing!
dogmaphobic's avatar
dogmaphobic committed
411

412
        int largestCompParamCount = 0;
413
        foreach(int componentId, _mapParameterName2Variant.keys()) {
414 415 416
            int compParamCount = _mapParameterName2Variant[componentId].count();
            if (compParamCount > largestCompParamCount) {
                largestCompParamCount = compParamCount;
417 418 419
                _defaultComponentId = componentId;
            }
        }
420

421
        if (_defaultComponentId == MAV_COMP_ID_ALL) {
422 423
            qWarning() << "All parameters missing, unable to determine default componet id";
        }
424 425 426 427
    }
}

/// Translates FactSystem::defaultComponentId to real component id if needed
428
int ParameterManager::_actualComponentId(int componentId)
429 430 431
{
    if (componentId == FactSystem::defaultComponentId) {
        componentId = _defaultComponentId;
Don Gagne's avatar
Don Gagne committed
432
        if (componentId == FactSystem::defaultComponentId) {
Don Gagne's avatar
Don Gagne committed
433 434
            qWarning() << "Default component id not set";
        }
435
    }
dogmaphobic's avatar
dogmaphobic committed
436

437 438 439
    return componentId;
}

440
void ParameterManager::refreshParameter(int componentId, const QString& name)
441
{
442
    componentId = _actualComponentId(componentId);
443
    qCDebug(ParameterManagerLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
444

445 446 447
    _dataMutex.lock();

    Q_ASSERT(_waitingReadParamNameMap.contains(componentId));
dogmaphobic's avatar
dogmaphobic committed
448

449
    if (_waitingReadParamNameMap.contains(componentId)) {
450 451 452 453
        QString mappedParamName = _remapParamNameToVersion(name);

        _waitingReadParamNameMap[componentId].remove(mappedParamName);  // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][mappedParamName] = 0;     // Add new wait entry and update retry count
454 455
        emit restartWaitingParamTimer();
    }
dogmaphobic's avatar
dogmaphobic committed
456

457 458 459
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
460 461
}

462
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
463 464
{
    componentId = _actualComponentId(componentId);
465
    qCDebug(ParameterManagerLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")";
466

467
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
468 469 470 471 472 473
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

474
bool ParameterManager::parameterExists(int componentId, const QString&  name)
475
{
476
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
477

478 479
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
480
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
481
    }
482 483

    return ret;
484 485
}

486
Fact* ParameterManager::getParameter(int componentId, const QString& name)
487 488
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
489

490 491 492
    QString mappedParamName = _remapParamNameToVersion(name);
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
493
        return &_defaultFact;
494
    }
dogmaphobic's avatar
dogmaphobic committed
495

496
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
497
}
498

499
QStringList ParameterManager::parameterNames(int componentId)
500
{
dogmaphobic's avatar
dogmaphobic committed
501 502
    QStringList names;

503
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
504 505 506 507
        names << paramName;
    }

    return names;
508 509
}

510
void ParameterManager::_setupGroupMap(void)
511
{
512 513 514
    // Must be able to handle being called multiple times
    _mapGroup2ParameterName.clear();

515
    foreach (int componentId, _mapParameterName2Variant.keys()) {
516
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
517 518 519 520 521 522
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

523
const QMap<int, QMap<QString, QStringList> >& ParameterManager::getGroupMap(void)
524 525 526
{
    return _mapGroup2ParameterName;
}
527

528
void ParameterManager::_waitingParamTimeout(void)
529 530 531 532
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;
dogmaphobic's avatar
dogmaphobic committed
533

534
    // First check for any missing parameters from the initial index based load
535 536
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
537 538
        foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
539
            if (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
540 541
                // Give up on this index
                _failedReadParamIndexMap[componentId] << paramIndex;
542
                qCDebug(ParameterManagerLog) << "Giving up on (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
543 544 545 546 547
                _waitingReadParamIndexMap[componentId].remove(paramIndex);
            } else {
                // Retry again
                paramsRequested = true;
                _readParameterRaw(componentId, "", paramIndex);
548
                qCDebug(ParameterManagerLog) << "Read re-request for (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
dogmaphobic's avatar
dogmaphobic committed
549

550 551 552
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
553 554 555
            }
        }
    }
556

557
    if (!paramsRequested && _defaultComponentId == MAV_COMP_ID_ALL && !_waitingForDefaultComponent) {
558 559 560 561 562 563 564 565 566 567
        // 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.
        _waitingParamTimeoutTimer.start();
        _waitingForDefaultComponent = true;
        return;
    }
    _waitingForDefaultComponent = false;

    // Check for initial load complete success/failure. Fail load if we don't have a default component at this point.
    _checkInitialLoadComplete(true /* failIfNoDefaultComponent */);
dogmaphobic's avatar
dogmaphobic committed
568

569 570
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
571
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
572
                paramsRequested = true;
573
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
574
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
575
                    _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue());
576
                    qCDebug(ParameterManagerLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
577 578 579 580 581 582 583
                    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));
584 585 586 587
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
588

589 590
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
591
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
592
                paramsRequested = true;
593
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
594 595
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
596
                    qCDebug(ParameterManagerLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
597 598 599 600 601 602 603
                    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));
604 605 606 607
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
608

609 610 611 612 613 614
Out:
    if (paramsRequested) {
        _waitingParamTimeoutTimer.start();
    }
}

615
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
616 617 618 619 620 621 622 623
{
    mavlink_message_t msg;
    char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];

    strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
    mavlink_msg_param_request_read_pack(_mavlink->getSystemId(),    // Our system id
                                        _mavlink->getComponentId(), // Our component id
                                        &msg,                       // Pack into this mavlink_message_t
624
                                        _vehicle->id(),             // Target system id
625 626 627
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
628
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
629 630
}

631
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
632 633 634
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
635

636
    FactMetaData::ValueType_t factType = getParameter(componentId, paramName)->type();
637
    p.param_type = _factTypeToMavType(factType);
dogmaphobic's avatar
dogmaphobic committed
638

639 640
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
641
            union_value.param_uint8 = (uint8_t)value.toUInt();
642
            break;
dogmaphobic's avatar
dogmaphobic committed
643

644
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
645
            union_value.param_int8 = (int8_t)value.toInt();
646
            break;
dogmaphobic's avatar
dogmaphobic committed
647

648
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
649
            union_value.param_uint16 = (uint16_t)value.toUInt();
650
            break;
dogmaphobic's avatar
dogmaphobic committed
651

652
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
653
            union_value.param_int16 = (int16_t)value.toInt();
654
            break;
dogmaphobic's avatar
dogmaphobic committed
655

656
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
657
            union_value.param_uint32 = (uint32_t)value.toUInt();
658
            break;
dogmaphobic's avatar
dogmaphobic committed
659

660 661 662
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
663

664 665 666
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
667

668
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
669
            union_value.param_int32 = (int32_t)value.toInt();
670 671
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
672

673
    p.param_value = union_value.param_float;
674
    p.target_system = (uint8_t)_vehicle->id();
675
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
676

677
    strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id));
dogmaphobic's avatar
dogmaphobic committed
678

679 680
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
681
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
682 683
}

684
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
685
{
686
    MapID2NamedParam cache_map;
687

688 689 690 691
    foreach(int id, _mapParameterId2Name[componentId].keys()) {
        const QString name(_mapParameterId2Name[componentId][id]);
        const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
        cache_map[id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue()));
692 693
    }

694
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
695 696 697 698 699 700
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

    QDataStream ds(&cache_file);
    ds << cache_map;
}

701
QDir ParameterManager::parameterCacheDir()
702 703 704 705 706
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

707
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
708
{
709
    return parameterCacheDir().filePath(QString("%1_%2").arg(vehicleId).arg(componentId));
710 711
}

712
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
713 714 715
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
716
    MapID2NamedParam cache_map;
717
    QFile cache_file(parameterCacheFile(vehicleId, componentId));
718
    if (!cache_file.exists()) {
719
        /* no local cache, just wait for them to come in*/
720 721 722 723 724 725 726 727 728
        return;
    }
    cache_file.open(QIODevice::ReadOnly);

    /* Deserialize the parameter cache table */
    QDataStream ds(&cache_file);
    ds >> cache_map;

    /* compute the crc of the local cache to check against the remote */
729 730 731 732 733 734 735

    foreach(int id, cache_map.keys()) {
        const QString name(cache_map[id].first);
        const void *vdat = cache_map[id].second.second.constData();
        const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.first);
        crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(),  crc32_value);
        crc32_value = QGC::crc32((const uint8_t *)vdat, FactMetaData::typeToSize(fact_type), crc32_value);
736 737 738
    }

    if (crc32_value == hash_value.toUInt()) {
739
        qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
740
        /* if the two param set hashes match, just load from the disk */
741 742 743 744 745 746
        int count = cache_map.count();
        foreach(int id, cache_map.keys()) {
            const QString &name = cache_map[id].first;
            const QVariant &value = cache_map[id].second.second;
            const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.first);
            const int mavType = _factTypeToMavType(fact_type);
747
            _parameterUpdate(vehicleId, componentId, name, count, id, mavType, value);
748
        }
749 750 751 752 753 754 755 756 757 758 759 760
        // Return the hash value to notify we don't want any more updates
        mavlink_param_set_t     p;
        mavlink_param_union_t   union_value;
        p.param_type = MAV_PARAM_TYPE_UINT32;
        strncpy(p.param_id, "_HASH_CHECK", sizeof(p.param_id));
        union_value.param_uint32 = crc32_value;
        p.param_value = union_value.param_float;
        p.target_system = (uint8_t)_vehicle->id();
        p.target_component = (uint8_t)componentId;
        mavlink_message_t msg;
        mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780

        // Give the user some feedback things loaded properly
        QVariantAnimation *ani = new QVariantAnimation(this);
        ani->setEasingCurve(QEasingCurve::OutCubic);
        ani->setStartValue(0.0);
        ani->setEndValue(1.0);
        ani->setDuration(750);

        connect(ani, &QVariantAnimation::valueChanged, [this](const QVariant &value) {
            emit parameterListProgress(value.toFloat());
        });

        // Hide 500ms after animation finishes
        connect(ani, &QVariantAnimation::finished, [this](){
            QTimer::singleShot(500, [this]() {
                emit parameterListProgress(0);
            });
        });

        ani->start(QAbstractAnimation::DeleteWhenStopped);
781 782 783
    }
}

784
void ParameterManager::_saveToEEPROM(void)
785
{
786 787
    if (_saveRequired) {
        _saveRequired = false;
788
        if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
789 790
            mavlink_message_t msg;
            mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
791
            _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
792
            qCDebug(ParameterManagerLog) << "_saveToEEPROM";
793
        } else {
794
            qCDebug(ParameterManagerLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
795
        }
Don Gagne's avatar
Don Gagne committed
796
    }
797 798
}

799
QString ParameterManager::readParametersFromStream(QTextStream& stream)
800
{
801
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
802

803 804 805 806 807 808
    while (!stream.atEnd()) {
        QString line = stream.readLine();
        if (!line.startsWith("#")) {
            QStringList wpParams = line.split("\t");
            int lineMavId = wpParams.at(0).toInt();
            if (wpParams.size() == 5) {
Don Gagne's avatar
Don Gagne committed
809 810
                if (_vehicle->id() != lineMavId) {
                    return QString("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.").arg(lineMavId).arg(_vehicle->id());
dogmaphobic's avatar
dogmaphobic committed
811 812
                }

813 814 815 816
                int     componentId = wpParams.at(1).toInt();
                QString paramName = wpParams.at(2);
                QString valStr = wpParams.at(3);
                uint    mavType = wpParams.at(4).toUInt();
dogmaphobic's avatar
dogmaphobic committed
817

818
                if (!parameterExists(componentId, paramName)) {
819 820 821
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
822
                    qCDebug(ParameterManagerLog) << error;
823 824
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
825

826
                Fact* fact = getParameter(componentId, paramName);
827
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
828 829 830
                    QString error;
                    error  = QString("Skipped parameter %1:%2 - type mismatch %3:%4\n").arg(componentId).arg(paramName).arg(fact->type()).arg(_mavTypeToFactType((MAV_PARAM_TYPE)mavType));
                    errors += error;
831
                    qCDebug(ParameterManagerLog) << error;
832 833
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
834

835
                qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
836
                fact->setRawValue(valStr);
837 838 839
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
840

841
    return errors;
842 843
}

844
void ParameterManager::writeParametersToStream(QTextStream &stream)
845
{
846
    stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
847 848 849 850
    stream << "#\n";
    stream << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    foreach (int componentId, _mapParameterName2Variant.keys()) {
851
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
852
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
853 854 855 856 857
            if (fact) {
                stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueStringFullPrecision() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
            } else {
                qWarning() << "Internal error: missing fact";
            }
858 859
        }
    }
dogmaphobic's avatar
dogmaphobic committed
860

861 862 863
    stream.flush();
}

864
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
865 866 867 868
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
869

870 871
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
872

873 874
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
875

876 877
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
878

879 880
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
881

882 883
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
884

885 886 887
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
888

889 890 891 892 893
        case FactMetaData::valueTypeInt32:
            return MAV_PARAM_TYPE_INT32;
    }
}

894
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
895 896 897 898
{
    switch (mavType) {
        case MAV_PARAM_TYPE_UINT8:
            return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
899

900 901
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
902

903 904
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
905

906 907
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
908

909 910
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
911

912 913
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
914

915 916 917
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
918

919 920 921 922 923
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

924
void ParameterManager::_restartWaitingParamTimer(void)
925 926 927
{
    _waitingParamTimeoutTimer.start();
}
928

929
void ParameterManager::_addMetaDataToDefaultComponent(void)
930
{
931
     if (_defaultComponentId == MAV_COMP_ID_ALL) {
932 933 934 935 936 937 938 939
         // We don't know what the default component is so we can't support meta data
         return;
     }

     if (_parameterMetaData) {
         return;
     }

Don Gagne's avatar
Don Gagne committed
940
     QString metaDataFile;
941
     int majorVersion, minorVersion;
Don Gagne's avatar
Don Gagne committed
942 943 944 945
     if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
         // Parameter versioning is still not really figured out correctly. We need to handle ArduPilot specially based on vehicle version.
         // The current three version are hardcoded in.
         metaDataFile = ((APMFirmwarePlugin*)_vehicle->firmwarePlugin())->getParameterMetaDataFile(_vehicle);
946
         qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile;
Don Gagne's avatar
Don Gagne committed
947 948 949
     } else {
         // Load best parameter meta data set
         metaDataFile = parameterMetaDataFile(_vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
950
         qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
Don Gagne's avatar
Don Gagne committed
951 952
     }

953 954 955 956 957 958 959 960 961
     _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);

    // Loop over all parameters in default component adding meta data
    QVariantMap& factMap = _mapParameterName2Variant[_defaultComponentId];
    foreach (const QString& key, factMap.keys()) {
        _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value<Fact*>(), _vehicle->vehicleType());
    }
}

962
/// @param failIfNoDefaultComponent true: Fails parameter load if no default component but we should have one
963
void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
964 965 966 967 968
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
969

970 971 972 973 974 975
    foreach (int componentId, _waitingReadParamIndexMap.keys()) {
        if (_waitingReadParamIndexMap[componentId].count()) {
            // We are still waiting on some parameters, not done yet
            return;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
976

977
    if (!failIfNoDefaultComponent && _defaultComponentId == MAV_COMP_ID_ALL) {
978 979 980 981
        // We are still waiting for default component to show up
        return;
    }

982 983
    // We aren't waiting for any more initial parameter updates, initial parameter loading is complete
    _initialLoadComplete = true;
dogmaphobic's avatar
dogmaphobic committed
984

985 986 987 988 989 990 991 992 993 994
    // Check for index based load failures
    QString indexList;
    bool initialLoadFailures = false;
    foreach (int componentId, _failedReadParamIndexMap.keys()) {
        foreach (int paramIndex, _failedReadParamIndexMap[componentId]) {
            if (initialLoadFailures) {
                indexList += ", ";
            }
            indexList += QString("%1").arg(paramIndex);
            initialLoadFailures = true;
995
            qCDebug(ParameterManagerLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")";
996 997
        }
    }
998 999

    _missingParameters = false;
1000
    if (initialLoadFailures) {
1001
        _missingParameters = true;
1002
        qgcApp()->showMessage("QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
dogmaphobic's avatar
dogmaphobic committed
1003
                              "This will cause QGroundControl to be unable to display its full user interface. "
1004 1005
                              "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.");
Don Gagne's avatar
Don Gagne committed
1006
        if (!qgcApp()->runningUnitTests()) {
1007
            qCWarning(ParameterManagerLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
Don Gagne's avatar
Don Gagne committed
1008
        }
1009 1010 1011
    } else if (_defaultComponentId == FactSystem::defaultComponentId && !_defaultComponentIdParam.isEmpty()) {
        // Missing default component when we should have one
        _missingParameters = true;
1012 1013 1014 1015
        qgcApp()->showMessage("QGroundControl did not receive parameters from the default component. "
                              "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.");
Don Gagne's avatar
Don Gagne committed
1016
        if (!qgcApp()->runningUnitTests()) {
1017
            qCWarning(ParameterManagerLog) << "Default component was never found, param:" << _defaultComponentIdParam;
Don Gagne's avatar
Don Gagne committed
1018
        }
1019 1020
    }

1021
    // Signal load complete
1022 1023
    _parametersReady = true;
    _determineDefaultComponentId();
1024 1025 1026
    _vehicle->autopilotPlugin()->parametersReadyPreChecks();
    emit parametersReadyChanged(true);
    emit missingParametersChanged(_missingParameters);
1027
}
1028

1029
void ParameterManager::_initialRequestTimeout(void)
1030
{
1031 1032 1033 1034 1035 1036 1037 1038
    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) {
        refreshAllParameters();
        _initialRequestTimeoutTimer.start();
    }
1039
}
1040

1041
QString ParameterManager::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057
{
    bool            cacheHit = false;
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    // Cached files are stored in settings location
    QSettings settings;
    QDir cacheDir = QFileInfo(settings.fileName()).dir();

    // First look for a direct cache hit
    int cacheMinorVersion, cacheMajorVersion;
    QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion)));
    if (cacheFile.exists()) {
        plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion);
        if (wantedMajorVersion != cacheMajorVersion) {
            qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion;
        } else {
1058
            qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090
            cacheHit = true;
        }
    }

    if (!cacheHit) {
        // No direct hit, look for lower param set version
        QString wildcard = QString("%1.%2.*.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType);
        QStringList cacheHits = cacheDir.entryList(QStringList(wildcard), QDir::Files, QDir::Name);

        // Find the highest major version number which is below the vehicles major version number
        int cacheHitIndex = -1;
        cacheMajorVersion = -1;
        QRegExp regExp(QString("%1\\.%2\\.(\\d*)\\.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType));
        for (int i=0; i< cacheHits.count(); i++) {
            if (regExp.exactMatch(cacheHits[i]) && regExp.captureCount() == 1) {
                int majorVersion = regExp.capturedTexts()[0].toInt();
                if (majorVersion > cacheMajorVersion && majorVersion < wantedMajorVersion) {
                    cacheMajorVersion = majorVersion;
                    cacheHitIndex = i;
                }
            }
        }

        if (cacheHitIndex != -1) {
            // We have a cache hit on a lower major version, read minor version as well
            int majorVersion;
            cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex]));
            plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion);
            if (majorVersion != cacheMajorVersion) {
                qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion;
                cacheHit = false;
            } else {
1091
                qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
1092 1093 1094 1095 1096 1097 1098 1099
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile();
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
1100
    qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131
    if (cacheHit) {
        // Cache hit is available, we need to check if internal meta data is a better match, if so use internal version
        if (internalMajorVersion == wantedMajorVersion) {
            if (cacheMajorVersion == wantedMajorVersion) {
                // Both internal and cache are direct hit on major version, Use higher minor version number
                cacheHit = cacheMinorVersion > internalMinorVersion;
            } else {
                // Direct internal hit, but not direct hit in cache, use internal
                cacheHit = false;
            }
        } else {
            if (cacheMajorVersion == wantedMajorVersion) {
                // Direct hit on cache, no direct hit on internal, use cache
                cacheHit = true;
            } else {
                // No direct hit anywhere, use internal
                cacheHit = false;
            }
        }
    }

    QString metaDataFile;
    if (cacheHit && !qgcApp()->runningUnitTests()) {
        majorVersion = cacheMajorVersion;
        minorVersion = cacheMinorVersion;
        metaDataFile = cacheFile.fileName();
    } else {
        majorVersion = internalMajorVersion;
        minorVersion = internalMinorVersion;
        metaDataFile = internalMetaDataFile;
    }
1132
    qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
1133 1134 1135 1136

    return metaDataFile;
}

1137
void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
1138 1139 1140 1141 1142
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
1143
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
1144 1145 1146

    // Find the cache hit closest to this new file
    int cacheMajorVersion, cacheMinorVersion;
1147 1148
    QString cacheHit = ParameterManager::parameterMetaDataFile(firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
    qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172

    bool cacheNewFile = false;
    if (cacheHit.isEmpty()) {
        // No cache hits, store the new file
        cacheNewFile = true;
    } else if (cacheMajorVersion == newMajorVersion) {
        // Direct hit on major version in cache:
        //      Cache new file if newer minor version
        //      Also delete older cache file
        if (newMinorVersion > cacheMinorVersion) {
            cacheNewFile = true;
            QFile::remove(cacheHit);
        }
    } else {
        // Indirect hit in cache, store new file
        cacheNewFile = true;
    }

    if (cacheNewFile) {
        // Cached files are stored in settings location. Copy from current file to cache naming.

        QSettings settings;
        QDir cacheDir = QFileInfo(settings.fileName()).dir();
        QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(newMajorVersion)));
1173
        qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
1174 1175 1176 1177
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}
1178 1179

/// Remap a parameter from one firmware version to another
1180
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191
{
    QString mappedParamName;

    if (!paramName.startsWith(QStringLiteral("r."))) {
        // No version mapping wanted
        return paramName;
    }

    int majorVersion = _vehicle->firmwareMajorVersion();
    int minorVersion = _vehicle->firmwareMinorVersion();

1192
    qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204

    mappedParamName = paramName.right(paramName.count() - 2);

    if (majorVersion == Vehicle::versionNotSetValue) {
        // Vehicle version unknown
        return mappedParamName;
    }

    const FirmwarePlugin::remapParamNameMajorVersionMap_t& majorVersionRemap = _vehicle->firmwarePlugin()->paramNameRemapMajorVersionMap();

    if (!majorVersionRemap.contains(majorVersion)) {
        // No mapping for this major version
1205
        qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1206 1207 1208 1209 1210
        return mappedParamName;
    }

    const FirmwarePlugin::remapParamNameMinorVersionRemapMap_t& remapMinorVersion = majorVersionRemap[majorVersion];

1211
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1212 1213 1214 1215 1216 1217 1218

    for (int currentMinorVersion=_vehicle->firmwarePlugin()->remapParamNameHigestMinorVersionNumber(majorVersion); currentMinorVersion>minorVersion; currentMinorVersion--) {
        if (remapMinorVersion.contains(currentMinorVersion)) {
            const FirmwarePlugin::remapParamNameMap_t& remap = remapMinorVersion[currentMinorVersion];

            if (remap.contains(mappedParamName)) {
                QString toParamName = remap[mappedParamName];
1219
                qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
1220 1221 1222 1223 1224 1225 1226
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1227 1228

/// The offline editing vehicle can have custom loaded params bolted into it.
1229
void ParameterManager::_loadOfflineEditingParams(void)
1230 1231 1232 1233 1234 1235 1236 1237
{    
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
1238
        qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286
    }

    QTextStream paramStream(&paramFile);

    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();

        if (line.startsWith("#")) {
            continue;
        }

        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);

        _defaultComponentId = paramData.at(1).toInt();
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        MAV_PARAM_TYPE paramType = static_cast<MAV_PARAM_TYPE>(paramData.at(4).toUInt());

        QVariant paramValue;
        switch (paramType) {
        case MAV_PARAM_TYPE_REAL32:
            paramValue = QVariant(valStr.toFloat());
            break;
        case MAV_PARAM_TYPE_UINT32:
            paramValue = QVariant(valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT32:
            paramValue = QVariant(valStr.toInt());
            break;
        case MAV_PARAM_TYPE_UINT16:
            paramValue = QVariant((quint16)valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT16:
            paramValue = QVariant((qint16)valStr.toInt());
            break;
        case MAV_PARAM_TYPE_UINT8:
            paramValue = QVariant((quint8)valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT8:
            paramValue = QVariant((qint8)valStr.toUInt());
            break;
        default:
            qCritical() << "Unknown type" << paramType;
            paramValue = QVariant(valStr.toInt());
            break;
        }

1287 1288 1289 1290 1291
        // Get parameter set version
        if (!_versionParam.isEmpty() && _versionParam == paramName) {
            _parameterSetMajorVersion = paramValue.toInt();
        }

1292 1293 1294 1295 1296
        Fact* fact = new Fact(_defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
        _mapParameterName2Variant[_defaultComponentId][paramName] = QVariant::fromValue(fact);
    }

    _addMetaDataToDefaultComponent();
1297
    _setupGroupMap();
1298 1299 1300
    _parametersReady = true;
    _initialLoadComplete = true;
}
1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340

void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject)
{
    QList<int>  rgCompIds;
    QStringList rgParamNames;

    if (componentId == MAV_COMP_ID_ALL) {
        rgCompIds = _mapParameterName2Variant.keys();
    } else {
        rgCompIds.append(_actualComponentId(componentId));
    }

    QJsonArray rgParams;

    // Loop over all requested component ids
    for (int i=0; i<rgCompIds.count(); i++) {
        int compId = rgCompIds[i];

        if (!_mapParameterName2Variant.contains(compId)) {
            qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson no params for compId" << compId;
            continue;
        }

        // Build list of parameter names if not specified
        if (paramsToSave.count() == 0) {
            rgParamNames = 	parameterNames(compId);
        } else {
            rgParamNames = paramsToSave;
        }

        // Loop over parameter names adding each to json array
        for (int j=0; j<rgParamNames.count(); j++) {
            QString paramName = rgParamNames[j];

            if (!parameterExists(compId, paramName)) {
                qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson param not found compId:param" << compId << paramName;
                continue;
            }

            QJsonObject paramJson;
1341
            Fact* fact = getParameter(compId, paramName);
1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399
            paramJson.insert(_jsonCompIdKey, QJsonValue(compId));
            paramJson.insert(_jsonParamNameKey, QJsonValue(fact->name()));
            paramJson.insert(_jsonParamValueKey, QJsonValue(fact->rawValue().toDouble()));

            rgParams.append(QJsonValue(paramJson));
        }
    }

    saveObject.insert(_jsonParametersKey, QJsonValue(rgParams));
}

bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QString& errorString)
{
    QList<QJsonValue::Type> keyTypes;

    errorString.clear();

    if (required) {
        if (!JsonHelper::validateRequiredKeys(json, QStringList(_jsonParametersKey), errorString)) {
            return false;
        }
    } else if (!json.contains(_jsonParametersKey)) {
        return true;
    }

    keyTypes = { QJsonValue::Array };
    if (!JsonHelper::validateKeyTypes(json, QStringList(_jsonParametersKey), keyTypes, errorString)) {
        return false;
    }

    QJsonArray rgParams = json[_jsonParametersKey].toArray();
    for (int i=0; i<rgParams.count(); i++) {
        QJsonValueRef paramValue = rgParams[i];

        if (!paramValue.isObject()) {
            errorString = tr("%1 key is not a json object").arg(_jsonParametersKey);
            return false;
        }
        QJsonObject param = paramValue.toObject();

        QStringList requiredKeys = { _jsonCompIdKey, _jsonParamNameKey, _jsonParamValueKey };
        if (!JsonHelper::validateRequiredKeys(param, requiredKeys, errorString)) {
            return false;
        }
        keyTypes = { QJsonValue::Double, QJsonValue::String, QJsonValue::Double };
        if (!JsonHelper::validateKeyTypes(param, requiredKeys, keyTypes, errorString)) {
            return false;
        }

        int compId = param[_jsonCompIdKey].toInt();
        QString name = param[_jsonParamNameKey].toString();
        double value = param[_jsonParamValueKey].toDouble();

        if (!parameterExists(compId, name)) {
            qCDebug(ParameterManagerLog) << "ParameterManager::loadFromJson param not found compId:param" << compId << name;
            continue;
        }

1400
        Fact* fact = getParameter(compId, name);
1401 1402 1403 1404 1405 1406
        fact->setRawValue(value);
    }

    return true;
}

1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425
void ParameterManager::resetAllParametersToDefaults(void)
{
    mavlink_message_t msg;
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();

    mavlink_msg_command_long_pack(mavlink->getSystemId(),
                                  mavlink->getComponentId(),
                                  &msg,
                                  _vehicle->id(),                   // Target systeem
                                  _vehicle->defaultComponentId(),   // Target component
                                  MAV_CMD_PREFLIGHT_STORAGE,
                                  0,                                // Confirmation
                                  2,                                // 2 = Reset params to default
                                  -1,                               // -1 = No change to mission storage
                                  0,                                // 0 = Ignore
                                  0, 0, 0, 0);                      // Unused
    _vehicle->sendMessageOnPriorityLink(msg);
}