ParameterLoader.cc 52.6 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 14 15 16

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

#include "ParameterLoader.h"
#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

23
#include <QEasingCurve>
24 25
#include <QFile>
#include <QDebug>
26
#include <QVariantAnimation>
27

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

33
QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog")
34

Don Gagne's avatar
Don Gagne committed
35 36
Fact ParameterLoader::_defaultFact;

Don Gagne's avatar
Don Gagne committed
37
const char* ParameterLoader::_cachedMetaDataFilePrefix = "ParameterFactMetaData";
38 39 40

ParameterLoader::ParameterLoader(Vehicle* vehicle)
    : QObject(vehicle)
41
    , _vehicle(vehicle)
42
    , _mavlink(NULL)
43 44
    , _parametersReady(false)
    , _initialLoadComplete(false)
45
    , _waitingForDefaultComponent(false)
46
    , _saveRequired(false)
47
    , _defaultComponentId(MAV_COMP_ID_ALL)
48 49
    , _parameterSetMajorVersion(-1)
    , _parameterMetaData(NULL)
Don Gagne's avatar
Don Gagne committed
50 51 52
    , _prevWaitingReadParamIndexCount(0)
    , _prevWaitingReadParamNameCount(0)
    , _prevWaitingWriteParamNameCount(0)
53
    , _initialRequestRetryCount(0)
54
    , _totalParamCount(0)
55
{
56 57 58 59 60 61
    if (_vehicle->isOfflineEditingVehicle()) {
        _loadOfflineEditingParams();
        return;
    }

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

63 64
    // We signal this to ouselves in order to start timer on our thread
    connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer);
dogmaphobic's avatar
dogmaphobic committed
65

66 67 68 69
    _initialRequestTimeoutTimer.setSingleShot(true);
    _initialRequestTimeoutTimer.setInterval(6000);
    connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_initialRequestTimeout);

70
    _waitingParamTimeoutTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
71
    _waitingParamTimeoutTimer.setInterval(1000);
72
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout);
73

74
    connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterLoader::_parameterUpdate);
75

76 77
    _versionParam = vehicle->firmwarePlugin()->getVersionParam();
    _defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
78
    qCDebug(ParameterLoaderLog) << "Default component param" << _defaultComponentIdParam;
79

80 81 82
    // Ensure the cache directory exists
    QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
    refreshAllParameters();
83 84 85 86
}

ParameterLoader::~ParameterLoader()
{
87
    delete _parameterMetaData;
88 89 90
}

/// Called whenever a parameter is updated or first seen.
91
void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
92 93
{
    // Is this for our uas?
94
    if (uasId != _vehicle->id()) {
95 96
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
97

98 99
    _initialRequestTimeoutTimer.stop();

Don Gagne's avatar
Don Gagne committed
100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119
    if (_initialLoadComplete) {
        qCDebug(ParameterLoaderLog) << "_parameterUpdate (id:" << uasId <<
                                        "componentId:" << componentId <<
                                        "name:" << parameterName <<
                                        "count:" << parameterCount <<
                                        "index:" << parameterId <<
                                        "mavType:" << mavType <<
                                        "value:" << value <<
                                        ")";
    } else {
        // This is too noisy during initial load
        qCDebug(ParameterLoaderVerboseLog) << "_parameterUpdate (id:" << uasId <<
                                       "componentId:" << componentId <<
                                       "name:" << parameterName <<
                                       "count:" << parameterCount <<
                                       "index:" << parameterId <<
                                       "mavType:" << mavType <<
                                       "value:" << value <<
                                       ")";
    }
dogmaphobic's avatar
dogmaphobic committed
120

121 122 123
#if 0
    // Handy for testing retry logic
    static int counter = 0;
124
    if (counter++ & 0x8) {
125 126 127 128
        qCDebug(ParameterLoaderLog) << "Artificial discard" << counter;
        return;
    }
#endif
129

130 131 132 133 134 135 136
#if 0
    // Use this to test missing default component id
    if (componentId == 50) {
        return;
    }
#endif

Don Gagne's avatar
Don Gagne committed
137
    if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
138
        /* we received a cache hash, potentially load from cache */
139
        _tryCacheHashLoad(uasId, componentId, value);
140 141
        return;
    }
142
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
143

144 145 146 147 148
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
149 150

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

152 153
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
154 155 156 157
        // 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;
158
        }
dogmaphobic's avatar
dogmaphobic committed
159

160 161 162
        // 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
163

164 165
        qCDebug(ParameterLoaderLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
    }
dogmaphobic's avatar
dogmaphobic committed
166

167 168 169 170 171 172 173 174 175 176 177 178
    // Determine default component id
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
        qCDebug(ParameterLoaderLog) << "Default component id determined" << componentId;
        _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;
    }

179 180 181 182 183 184 185 186
    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();
    }

187
    // Remove this parameter from the waiting lists
188 189 190
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
191
    qCDebug(ParameterLoaderVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
192 193 194 195
    qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];

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

197 198 199
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
200

201 202 203 204 205 206 207
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
    }

dogmaphobic's avatar
dogmaphobic committed
208

209 210 211 212 213 214
    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
215

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

Don Gagne's avatar
Don Gagne committed
223 224 225 226
    int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
    int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
    if (totalWaitingParamCount) {
        qCDebug(ParameterLoaderLog) << "totalWaitingParamCount:" << totalWaitingParamCount;
227
    } else if (_defaultComponentId != MAV_COMP_ID_ALL) {
228 229
        // No more parameters to wait for, stop the timeout. Be careful to not stop timer if we don't have the default
        // component yet.
230 231 232
        _waitingParamTimeoutTimer.stop();
    }

Don Gagne's avatar
Don Gagne committed
233 234 235 236 237 238 239
    // 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);
        }
240
    } else {
Don Gagne's avatar
Don Gagne committed
241
        emit parameterListProgress((float)(_totalParamCount - readWaitingParamCount) / (float)_totalParamCount);
242
    }
dogmaphobic's avatar
dogmaphobic committed
243

244 245 246 247 248
    // Get parameter set version
    if (!_versionParam.isEmpty() && _versionParam == parameterName) {
        _parameterSetMajorVersion = value.toInt();
    }

249
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
250
        qCDebug(ParameterLoaderLog) << "Adding new fact";
dogmaphobic's avatar
dogmaphobic committed
251

252 253 254 255 256 257
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
258
                factType = FactMetaData::valueTypeInt8;
259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282
                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
283

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

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

288
        // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
Don Gagne's avatar
Don Gagne committed
289
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterLoader::_valueUpdated);
290
    }
dogmaphobic's avatar
dogmaphobic committed
291

Don Gagne's avatar
Don Gagne committed
292 293
    _dataMutex.unlock();

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

296 297
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
298
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
299

300 301 302 303 304 305 306 307 308 309 310 311 312
    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
313 314
    if (_prevWaitingWriteParamNameCount != 0 &&  waitingWriteParamNameCount == 0) {
        // If all the writes just finished the vehicle is up to date, so persist.
315 316
        _saveToEEPROM();
    }
dogmaphobic's avatar
dogmaphobic committed
317

Don Gagne's avatar
Don Gagne committed
318 319 320 321 322 323 324 325 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
            _writeLocalParamCache(uasId, componentId);
        }
    }

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

332 333
    // Don't fail initial load complete if default component isn't found yet. That will be handled in wait timeout check.
    _checkInitialLoadComplete(false /* failIfNoDefaultComponent */);
334 335 336 337
}

/// Connected to Fact::valueUpdated
///
338
/// Writes the parameter to mavlink, sets up for write wait
339 340 341 342
void ParameterLoader::_valueUpdated(const QVariant& value)
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
343

344
    int componentId = fact->componentId();
345
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
346

347
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
348

349
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
350 351
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
352
    _waitingParamTimeoutTimer.start();
353
    _saveRequired = true;
dogmaphobic's avatar
dogmaphobic committed
354

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

357 358
    _writeParameterRaw(componentId, fact->name(), value);
    qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
359

360 361
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
        qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
362
    }
363 364
}

dogmaphobic's avatar
dogmaphobic committed
365
void ParameterLoader::refreshAllParameters(uint8_t componentID)
366
{
367
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
368

369 370 371 372
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

373
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
374
    foreach (int cid, _paramCountMap.keys()) {
375
        // Add/Update all indices to the wait list, parameter index is 0-based
dogmaphobic's avatar
dogmaphobic committed
376 377 378
        if(componentID != MAV_COMP_ID_ALL && componentID != cid)
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
379
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
380
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
381 382
        }
    }
dogmaphobic's avatar
dogmaphobic committed
383

384
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
385

386
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
387
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
388

389
    mavlink_message_t msg;
dogmaphobic's avatar
dogmaphobic committed
390
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), componentID);
391
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
392

dogmaphobic's avatar
dogmaphobic committed
393 394
    QString what = (componentID == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentID);
    qCDebug(ParameterLoaderLog) << "Request to refresh all parameters for component ID:" << what;
395 396 397 398
}

void ParameterLoader::_determineDefaultComponentId(void)
{
399
    if (_defaultComponentId == MAV_COMP_ID_ALL) {
400 401 402
        // 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
403

404
        int largestCompParamCount = 0;
405
        foreach(int componentId, _mapParameterName2Variant.keys()) {
406 407 408
            int compParamCount = _mapParameterName2Variant[componentId].count();
            if (compParamCount > largestCompParamCount) {
                largestCompParamCount = compParamCount;
409 410 411
                _defaultComponentId = componentId;
            }
        }
412

413
        if (_defaultComponentId == MAV_COMP_ID_ALL) {
414 415
            qWarning() << "All parameters missing, unable to determine default componet id";
        }
416 417 418 419 420 421 422 423
    }
}

/// Translates FactSystem::defaultComponentId to real component id if needed
int ParameterLoader::_actualComponentId(int componentId)
{
    if (componentId == FactSystem::defaultComponentId) {
        componentId = _defaultComponentId;
Don Gagne's avatar
Don Gagne committed
424
        if (componentId == FactSystem::defaultComponentId) {
Don Gagne's avatar
Don Gagne committed
425 426
            qWarning() << "Default component id not set";
        }
427
    }
dogmaphobic's avatar
dogmaphobic committed
428

429 430 431 432 433
    return componentId;
}

void ParameterLoader::refreshParameter(int componentId, const QString& name)
{
434 435
    componentId = _actualComponentId(componentId);
    qCDebug(ParameterLoaderLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
dogmaphobic's avatar
dogmaphobic committed
436

437 438 439
    _dataMutex.lock();

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

441
    if (_waitingReadParamNameMap.contains(componentId)) {
442 443 444 445
        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
446 447
        emit restartWaitingParamTimer();
    }
dogmaphobic's avatar
dogmaphobic committed
448

449 450 451
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
452 453 454 455 456
}

void ParameterLoader::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
    componentId = _actualComponentId(componentId);
457 458
    qCDebug(ParameterLoaderLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")";

459
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
460 461 462 463 464 465
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

466
bool ParameterLoader::parameterExists(int componentId, const QString&  name)
467
{
468
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
469

470 471
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
472
        ret = _mapParameterName2Variant[componentId].contains(_remapParamNameToVersion(name));
473
    }
474 475

    return ret;
476 477 478 479 480
}

Fact* ParameterLoader::getFact(int componentId, const QString& name)
{
    componentId = _actualComponentId(componentId);
dogmaphobic's avatar
dogmaphobic committed
481

482 483 484
    QString mappedParamName = _remapParamNameToVersion(name);
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(mappedParamName)) {
        qgcApp()->reportMissingParameter(componentId, mappedParamName);
Don Gagne's avatar
Don Gagne committed
485
        return &_defaultFact;
486
    }
dogmaphobic's avatar
dogmaphobic committed
487

488
    return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
489
}
490

Don Gagne's avatar
Don Gagne committed
491
QStringList ParameterLoader::parameterNames(int componentId)
492
{
dogmaphobic's avatar
dogmaphobic committed
493 494
    QStringList names;

495
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
496 497 498 499
        names << paramName;
    }

    return names;
500 501 502 503
}

void ParameterLoader::_setupGroupMap(void)
{
504 505 506
    // Must be able to handle being called multiple times
    _mapGroup2ParameterName.clear();

507
    foreach (int componentId, _mapParameterName2Variant.keys()) {
508
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
509 510 511 512 513 514 515 516 517 518
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
    return _mapGroup2ParameterName;
}
519 520 521 522 523 524

void ParameterLoader::_waitingParamTimeout(void)
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;
dogmaphobic's avatar
dogmaphobic committed
525

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

542 543 544
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
545 546 547
            }
        }
    }
548

549
    if (!paramsRequested && _defaultComponentId == MAV_COMP_ID_ALL && !_waitingForDefaultComponent) {
550 551 552 553 554 555 556 557 558 559
        // 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
560

561 562
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
563
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
564
                paramsRequested = true;
565
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
566 567 568 569 570 571 572 573 574 575
                if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
                    qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "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));
576 577 578 579
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
580

581 582
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
583
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
584
                paramsRequested = true;
585
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
586 587 588 589 590 591 592 593 594 595
                if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
                    _readParameterRaw(componentId, paramName, -1);
                    qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "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));
596 597 598 599
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
600

601 602 603 604 605 606 607 608 609 610 611 612 613 614 615
Out:
    if (paramsRequested) {
        _waitingParamTimeoutTimer.start();
    }
}

void ParameterLoader::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
{
    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
616
                                        _vehicle->id(),             // Target system id
617 618 619
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
620
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
621 622 623 624 625 626
}

void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
dogmaphobic's avatar
dogmaphobic committed
627

628
    FactMetaData::ValueType_t factType = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->type();
629
    p.param_type = _factTypeToMavType(factType);
dogmaphobic's avatar
dogmaphobic committed
630

631 632
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
633
            union_value.param_uint8 = (uint8_t)value.toUInt();
634
            break;
dogmaphobic's avatar
dogmaphobic committed
635

636
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
637
            union_value.param_int8 = (int8_t)value.toInt();
638
            break;
dogmaphobic's avatar
dogmaphobic committed
639

640
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
641
            union_value.param_uint16 = (uint16_t)value.toUInt();
642
            break;
dogmaphobic's avatar
dogmaphobic committed
643

644
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
645
            union_value.param_int16 = (int16_t)value.toInt();
646
            break;
dogmaphobic's avatar
dogmaphobic committed
647

648
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
649
            union_value.param_uint32 = (uint32_t)value.toUInt();
650
            break;
dogmaphobic's avatar
dogmaphobic committed
651

652 653 654
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
655

656 657 658
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
659

660
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
661
            union_value.param_int32 = (int32_t)value.toInt();
662 663
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
664

665
    p.param_value = union_value.param_float;
666
    p.target_system = (uint8_t)_vehicle->id();
667
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
668

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

671 672
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
673
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
674 675
}

676
void ParameterLoader::_writeLocalParamCache(int uasId, int componentId)
677
{
678
    MapID2NamedParam cache_map;
679

680 681 682 683
    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()));
684 685
    }

686
    QFile cache_file(parameterCacheFile(uasId, componentId));
687 688 689 690 691 692
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

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

693 694 695 696 697 698 699
QDir ParameterLoader::parameterCacheDir()
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

QString ParameterLoader::parameterCacheFile(int uasId, int componentId)
700
{
701
    return parameterCacheDir().filePath(QString("%1_%2").arg(uasId).arg(componentId));
702 703
}

704
void ParameterLoader::_tryCacheHashLoad(int uasId, int componentId, QVariant hash_value)
705 706 707
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
708 709
    MapID2NamedParam cache_map;
    QFile cache_file(parameterCacheFile(uasId, componentId));
710
    if (!cache_file.exists()) {
711
        /* no local cache, just wait for them to come in*/
712 713 714 715 716 717 718 719 720
        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 */
721 722 723 724 725 726 727

    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);
728 729 730
    }

    if (crc32_value == hash_value.toUInt()) {
731
        qCInfo(ParameterLoaderLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
732
        /* if the two param set hashes match, just load from the disk */
733 734 735 736 737 738 739
        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);
            _parameterUpdate(uasId, componentId, name, count, id, mavType, value);
740
        }
741 742 743 744 745 746 747 748 749 750 751 752
        // 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);
753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772

        // 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);
773 774 775
    }
}

776 777
void ParameterLoader::_saveToEEPROM(void)
{
778 779
    if (_saveRequired) {
        _saveRequired = false;
780
        if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
781 782
            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);
783
            _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
784 785 786 787
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
        } else {
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
        }
Don Gagne's avatar
Don Gagne committed
788
    }
789 790
}

791
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
792
{
793
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
794

795 796 797 798 799 800
    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
801 802
                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
803 804
                }

805 806 807 808
                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
809

810
                if (!_vehicle->autopilotPlugin()->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
811 812 813 814
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
                    qCDebug(ParameterLoaderLog) << error;
815 816
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
817

818
                Fact* fact = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName);
819
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
820 821 822 823
                    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;
                    qCDebug(ParameterLoaderLog) << error;
824 825
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
826

827
                qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
828
                fact->setRawValue(valStr);
829 830 831
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
832

833
    return errors;
834 835
}

836
void ParameterLoader::writeParametersToStream(QTextStream &stream)
837
{
838
    stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
839 840 841 842
    stream << "#\n";
    stream << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    foreach (int componentId, _mapParameterName2Variant.keys()) {
843
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
844
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
845 846 847 848 849
            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";
            }
850 851
        }
    }
dogmaphobic's avatar
dogmaphobic committed
852

853 854 855 856 857 858 859 860
    stream.flush();
}

MAV_PARAM_TYPE ParameterLoader::_factTypeToMavType(FactMetaData::ValueType_t factType)
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
dogmaphobic's avatar
dogmaphobic committed
861

862 863
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
864

865 866
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
867

868 869
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
870

871 872
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
873

874 875
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
876

877 878 879
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
880

881 882 883 884 885 886 887 888 889 890
        case FactMetaData::valueTypeInt32:
            return MAV_PARAM_TYPE_INT32;
    }
}

FactMetaData::ValueType_t ParameterLoader::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
{
    switch (mavType) {
        case MAV_PARAM_TYPE_UINT8:
            return FactMetaData::valueTypeUint8;
dogmaphobic's avatar
dogmaphobic committed
891

892 893
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
894

895 896
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
897

898 899
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
900

901 902
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
903

904 905
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
906

907 908 909
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
910

911 912 913 914 915 916 917 918 919
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

void ParameterLoader::_restartWaitingParamTimer(void)
{
    _waitingParamTimeoutTimer.start();
}
920

921
void ParameterLoader::_addMetaDataToDefaultComponent(void)
922
{
923
     if (_defaultComponentId == MAV_COMP_ID_ALL) {
924 925 926 927 928 929 930 931
         // 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
932
     QString metaDataFile;
933
     int majorVersion, minorVersion;
Don Gagne's avatar
Don Gagne committed
934 935 936 937 938 939 940 941 942 943 944
     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);
         qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile;
     } else {
         // Load best parameter meta data set
         metaDataFile = parameterMetaDataFile(_vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
         qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
     }

945 946 947 948 949 950 951 952 953
     _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());
    }
}

954 955
/// @param failIfNoDefaultComponent true: Fails parameter load if no default component but we should have one
void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
956 957 958 959 960
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
961

962 963 964 965 966 967
    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
968

969
    if (!failIfNoDefaultComponent && _defaultComponentId == MAV_COMP_ID_ALL) {
970 971 972 973
        // We are still waiting for default component to show up
        return;
    }

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

977 978 979 980 981 982 983 984 985 986 987 988 989
    // 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;
            qCDebug(ParameterLoaderLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")";
        }
    }
990
    if (initialLoadFailures) {
991
        qgcApp()->showMessage("QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
dogmaphobic's avatar
dogmaphobic committed
992
                              "This will cause QGroundControl to be unable to display its full user interface. "
993 994
                              "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
995 996 997 998
        if (!qgcApp()->runningUnitTests()) {
            qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
        }
        emit parametersReady(true /* missingParameters */);
999
        return;
1000
    }
1001 1002 1003 1004 1005 1006 1007

    // Check for missing default component when we should have one
    if (_defaultComponentId == FactSystem::defaultComponentId && !_defaultComponentIdParam.isEmpty()) {
        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
1008 1009 1010 1011
        if (!qgcApp()->runningUnitTests()) {
            qCWarning(ParameterLoaderLog) << "Default component was never found, param:" << _defaultComponentIdParam;
        }
        emit parametersReady(true /* missingParameters */);
1012 1013 1014 1015 1016 1017
        return;
    }

    // No failures, signal good load
    _parametersReady = true;
    _determineDefaultComponentId();
Don Gagne's avatar
Don Gagne committed
1018
    emit parametersReady(false /* no missingParameters */);
1019
}
1020 1021 1022

void ParameterLoader::_initialRequestTimeout(void)
{
1023 1024 1025 1026 1027 1028 1029 1030
    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();
    }
1031
}
1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 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 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 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 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169

QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
{
    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 {
            qCDebug(ParameterLoaderLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
            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 {
                qCDebug(ParameterLoaderLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
                cacheHit = true;
            }
        }
    }

    int internalMinorVersion, internalMajorVersion;
    QString internalMetaDataFile = plugin->internalParameterMetaDataFile();
    plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
    qCDebug(ParameterLoaderLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
    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;
    }
    qCDebug(ParameterLoaderLog) << "ParameterLoader::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;

    return metaDataFile;
}

void ParameterLoader::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
{
    FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);

    int newMajorVersion, newMinorVersion;
    plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
    qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;

    // Find the cache hit closest to this new file
    int cacheMajorVersion, cacheMinorVersion;
    QString cacheHit = ParameterLoader::parameterMetaDataFile(firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
    qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;

    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)));
        qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile caching file:" << cacheFile.fileName();
        QFile newFile(metaDataFile);
        newFile.copy(cacheFile.fileName());
    }
}
1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202

/// Remap a parameter from one firmware version to another
QString ParameterLoader::_remapParamNameToVersion(const QString& paramName)
{
    QString mappedParamName;

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

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

    qCDebug(ParameterLoaderLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;

    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
        qCDebug(ParameterLoaderLog) << "_remapParamNameToVersion: no major version mapping";
        return mappedParamName;
    }

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

1203
    // We must map backwards from the highest known minor version to one above the vehicle's minor version
1204 1205 1206 1207 1208 1209 1210 1211 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];
                qCDebug(ParameterLoaderLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
                mappedParamName = toParamName;
            }
        }
    }

    return mappedParamName;
}
1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 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

/// The offline editing vehicle can have custom loaded params bolted into it.
void ParameterLoader::_loadOfflineEditingParams(void)
{    
    QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
    if (paramFilename.isEmpty()) {
        return;
    }

    QFile paramFile(paramFilename);
    if (!paramFile.open(QFile::ReadOnly)) {
        qCWarning(ParameterLoaderLog) << "Unable to open offline editing params file" << paramFilename;
    }

    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;
        }

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

    _addMetaDataToDefaultComponent();
    _parametersReady = true;
    _initialLoadComplete = true;
}