ParameterLoader.cc 33.8 KB
Newer Older
1
/*=====================================================================
dogmaphobic's avatar
dogmaphobic committed
2

3
 QGroundControl Open Source Ground Control Station
dogmaphobic's avatar
dogmaphobic committed
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic's avatar
dogmaphobic committed
6

7
 This file is part of the QGROUNDCONTROL project
dogmaphobic's avatar
dogmaphobic committed
8

9 10 11 12
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
dogmaphobic's avatar
dogmaphobic committed
13

14 15 16 17
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
dogmaphobic's avatar
dogmaphobic committed
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic's avatar
dogmaphobic committed
21

22 23 24 25 26 27 28 29
 ======================================================================*/

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

#include "ParameterLoader.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
30
#include "QGCApplication.h"
31
#include "UASMessageHandler.h"
Don Gagne's avatar
Don Gagne committed
32
#include "FirmwarePlugin.h"
33
#include "UAS.h"
34 35 36 37

#include <QFile>
#include <QDebug>

38 39 40 41 42
/* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;

43
QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")
44
QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog")
45

Don Gagne's avatar
Don Gagne committed
46 47
Fact ParameterLoader::_defaultFact;

48 49 50 51 52
ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent)
    : QObject(parent)
    , _autopilot(autopilot)
    , _vehicle(vehicle)
    , _mavlink(qgcApp()->toolbox()->mavlinkProtocol())
53
    , _dedicatedLink(_vehicle->priorityLink())
54 55
    , _parametersReady(false)
    , _initialLoadComplete(false)
56
    , _saveRequired(false)
57 58
    , _defaultComponentId(FactSystem::defaultComponentId)
    , _totalParamCount(0)
59
{
60
    Q_ASSERT(_autopilot);
61
    Q_ASSERT(_vehicle);
62
    Q_ASSERT(_mavlink);
dogmaphobic's avatar
dogmaphobic committed
63

64 65
    // 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
66

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

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

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

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

ParameterLoader::~ParameterLoader()
{

}

/// Called whenever a parameter is updated or first seen.
88
void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
89 90
{
    bool setMetaData = false;
dogmaphobic's avatar
dogmaphobic committed
91

92
    // Is this for our uas?
93
    if (uasId != _vehicle->id()) {
94 95
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
96

97 98
    _initialRequestTimeoutTimer.stop();

99 100 101 102 103 104 105 106
    qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId <<
                                    "componentId:" << componentId <<
                                    "name:" << parameterName <<
                                    "count:" << parameterCount <<
                                    "index:" << parameterId <<
                                    "mavType:" << mavType <<
                                    "value:" << value <<
                                    ")";
dogmaphobic's avatar
dogmaphobic committed
107

108 109 110 111 112 113 114 115
#if 0
    // Handy for testing retry logic
    static int counter = 0;
    if (counter++ & 0x3) {
        qCDebug(ParameterLoaderLog) << "Artificial discard" << counter;
        return;
    }
#endif
116 117 118

    if (parameterName == "_HASH_CHECK") {
        /* we received a cache hash, potentially load from cache */
119
        _tryCacheHashLoad(uasId, componentId, value);
120 121
        return;
    }
122
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
123

124 125
    // Restart our waiting for param timer
    _waitingParamTimeoutTimer.start();
dogmaphobic's avatar
dogmaphobic committed
126

127 128 129 130 131
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
132 133

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

135 136
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
137 138 139 140
        // 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;
141
        }
dogmaphobic's avatar
dogmaphobic committed
142

143 144 145
        // 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
146

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

150
    // Remove this parameter from the waiting lists
151 152 153
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
154
    qCDebug(ParameterLoaderVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
155 156 157 158
    qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];

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

160 161 162
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
dogmaphobic's avatar
dogmaphobic committed
163

164 165 166 167 168 169 170
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
    }

dogmaphobic's avatar
dogmaphobic committed
171

172 173 174 175 176 177
    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
178

179 180 181 182 183 184
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
    }
dogmaphobic's avatar
dogmaphobic committed
185

186 187 188 189 190 191 192 193 194 195 196 197 198 199
    int waitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount + waitingWriteParamNameCount;
    if (waitingParamCount) {
        qCDebug(ParameterLoaderLog) << "waitingParamCount:" << waitingParamCount;
    } else {
        // No more parameters to wait for, stop the timeout
        _waitingParamTimeoutTimer.stop();
    }

    // Update progress bar
    if (waitingParamCount == 0) {
        emit parameterListProgress(0);
    } else {
        emit parameterListProgress((float)(_totalParamCount - waitingParamCount) / (float)_totalParamCount);
    }
dogmaphobic's avatar
dogmaphobic committed
200

201 202
    // Attempt to determine default component id
    if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) {
203
        _defaultComponentIdParam = _vehicle->firmwarePlugin()->getDefaultComponentIdParam();
204 205 206 207
    }
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
        _defaultComponentId = componentId;
    }
dogmaphobic's avatar
dogmaphobic committed
208

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

212 213 214 215 216 217
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
218
                factType = FactMetaData::valueTypeInt8;
219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242
                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
243

244 245
        Fact* fact = new Fact(componentId, parameterName, factType, this);
        setMetaData = true;
dogmaphobic's avatar
dogmaphobic committed
246

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

249
        // 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
250
        connect(fact, &Fact::_containerRawValueChanged, this, &ParameterLoader::_valueUpdated);
251
    }
dogmaphobic's avatar
dogmaphobic committed
252

Don Gagne's avatar
Don Gagne committed
253 254
    _dataMutex.unlock();

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

257 258
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
Don Gagne's avatar
Don Gagne committed
259
    fact->_containerSetRawValue(value);
dogmaphobic's avatar
dogmaphobic committed
260

261
    if (setMetaData) {
262
        _vehicle->firmwarePlugin()->addMetaDataToFact(fact, _vehicle->vehicleType());
263
    }
dogmaphobic's avatar
dogmaphobic committed
264

265 266 267
    if (waitingParamCount == 0) {
        // Now that we know vehicle is up to date persist
        _saveToEEPROM();
268
        _writeLocalParamCache(uasId, componentId);
269
    }
dogmaphobic's avatar
dogmaphobic committed
270

271
    _checkInitialLoadComplete();
272 273 274 275
}

/// Connected to Fact::valueUpdated
///
276
/// Writes the parameter to mavlink, sets up for write wait
277 278 279 280
void ParameterLoader::_valueUpdated(const QVariant& value)
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
281

282
    int componentId = fact->componentId();
283
    QString name = fact->name();
dogmaphobic's avatar
dogmaphobic committed
284

285
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
286

287
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
288 289
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
290
    _waitingParamTimeoutTimer.start();
291
    _saveRequired = true;
dogmaphobic's avatar
dogmaphobic committed
292

293
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
294

295 296
    _writeParameterRaw(componentId, fact->name(), value);
    qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
297

298 299
    if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
        qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
300
    }
301 302
}

dogmaphobic's avatar
dogmaphobic committed
303
void ParameterLoader::refreshAllParameters(uint8_t componentID)
304
{
305
    _dataMutex.lock();
dogmaphobic's avatar
dogmaphobic committed
306

307 308 309 310
    if (!_initialLoadComplete) {
        _initialRequestTimeoutTimer.start();
    }

311
    // Reset index wait lists
dogmaphobic's avatar
dogmaphobic committed
312
    foreach (int cid, _paramCountMap.keys()) {
313
        // Add/Update all indices to the wait list, parameter index is 0-based
dogmaphobic's avatar
dogmaphobic committed
314 315 316
        if(componentID != MAV_COMP_ID_ALL && componentID != cid)
            continue;
        for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
317
            // This will add a new waiting index if needed and set the retry count for that index to 0
dogmaphobic's avatar
dogmaphobic committed
318
            _waitingReadParamIndexMap[cid][waitingIndex] = 0;
319 320
        }
    }
dogmaphobic's avatar
dogmaphobic committed
321

322
    _dataMutex.unlock();
dogmaphobic's avatar
dogmaphobic committed
323

324
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
325
    Q_ASSERT(mavlink);
dogmaphobic's avatar
dogmaphobic committed
326

327
    mavlink_message_t msg;
dogmaphobic's avatar
dogmaphobic committed
328
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), componentID);
329
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
dogmaphobic's avatar
dogmaphobic committed
330

dogmaphobic's avatar
dogmaphobic committed
331 332
    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;
333 334 335 336 337 338 339 340
}

void ParameterLoader::_determineDefaultComponentId(void)
{
    if (_defaultComponentId == FactSystem::defaultComponentId) {
        // 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
341

342
        _defaultComponentId = -1;
343
        int largestCompParamCount = 0;
344
        foreach(int componentId, _mapParameterName2Variant.keys()) {
345 346 347
            int compParamCount = _mapParameterName2Variant[componentId].count();
            if (compParamCount > largestCompParamCount) {
                largestCompParamCount = compParamCount;
348 349 350
                _defaultComponentId = componentId;
            }
        }
351 352 353 354

        if (_defaultComponentId == -1) {
            qWarning() << "All parameters missing, unable to determine default componet id";
        }
355 356 357 358 359 360 361 362
    }
}

/// 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
363
        if (componentId == FactSystem::defaultComponentId) {
Don Gagne's avatar
Don Gagne committed
364 365
            qWarning() << "Default component id not set";
        }
366
    }
dogmaphobic's avatar
dogmaphobic committed
367

368 369 370 371 372
    return componentId;
}

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

376 377 378
    _dataMutex.lock();

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

380
    if (_waitingReadParamNameMap.contains(componentId)) {
381 382
        _waitingReadParamNameMap[componentId].remove(name); // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][name] = 0;    // Add new wait entry and update retry count
383 384
        emit restartWaitingParamTimer();
    }
dogmaphobic's avatar
dogmaphobic committed
385

386 387 388
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
389 390 391 392 393
}

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

396
    foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
397 398 399 400 401 402
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

403
bool ParameterLoader::parameterExists(int componentId, const QString&  name)
404
{
405
    bool ret = false;
dogmaphobic's avatar
dogmaphobic committed
406

407 408
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
409
        ret = _mapParameterName2Variant[componentId].contains(name);
410
    }
411 412

    return ret;
413 414 415 416 417
}

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

419
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(name)) {
Don Gagne's avatar
Don Gagne committed
420 421
        qgcApp()->reportMissingParameter(componentId, name);
        return &_defaultFact;
422
    }
dogmaphobic's avatar
dogmaphobic committed
423

Don Gagne's avatar
Don Gagne committed
424
    return _mapParameterName2Variant[componentId][name].value<Fact*>();
425
}
426

Don Gagne's avatar
Don Gagne committed
427
QStringList ParameterLoader::parameterNames(int componentId)
428
{
dogmaphobic's avatar
dogmaphobic committed
429 430
    QStringList names;

431
    foreach(const QString &paramName, _mapParameterName2Variant[_actualComponentId(componentId)].keys()) {
dogmaphobic's avatar
dogmaphobic committed
432 433 434 435
        names << paramName;
    }

    return names;
436 437 438 439 440
}

void ParameterLoader::_setupGroupMap(void)
{
    foreach (int componentId, _mapParameterName2Variant.keys()) {
441
        foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) {
442 443 444 445 446 447 448 449 450 451
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
    return _mapGroup2ParameterName;
}
452 453 454 455 456 457

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

459
    // We timed out waiting for some parameters from the initial set. Re-request those.
dogmaphobic's avatar
dogmaphobic committed
460

461 462
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
463 464 465 466 467 468 469 470 471 472 473 474
        foreach(int paramIndex, _waitingReadParamIndexMap[componentId].keys()) {
            _waitingReadParamIndexMap[componentId][paramIndex]++;   // Bump retry count
            if (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetry) {
                // 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
475

476 477 478
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
479 480 481
            }
        }
    }
482 483
    // We need to check for initial load complete here as well, since it could complete on a max retry failure
    _checkInitialLoadComplete();
dogmaphobic's avatar
dogmaphobic committed
484

485 486
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
487
            foreach(const QString &paramName, _waitingWriteParamNameMap[componentId].keys()) {
488
                paramsRequested = true;
489
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
Don Gagne's avatar
Don Gagne committed
490
                _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
491
                qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
492

493 494 495 496 497 498
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
499

500 501
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
502
            foreach(const QString &paramName, _waitingReadParamNameMap[componentId].keys()) {
503
                paramsRequested = true;
504
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
505
                _readParameterRaw(componentId, paramName, -1);
506
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
dogmaphobic's avatar
dogmaphobic committed
507

508 509 510 511 512 513
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
514

515 516 517 518 519 520 521 522 523 524 525 526 527 528 529
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
530
                                        _vehicle->id(),             // Target system id
531 532 533
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
534
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
535 536 537 538 539 540
}

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
541

542 543
    FactMetaData::ValueType_t factType = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->type();
    p.param_type = _factTypeToMavType(factType);
dogmaphobic's avatar
dogmaphobic committed
544

545 546
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
547
            union_value.param_uint8 = (uint8_t)value.toUInt();
548
            break;
dogmaphobic's avatar
dogmaphobic committed
549

550
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
551
            union_value.param_int8 = (int8_t)value.toInt();
552
            break;
dogmaphobic's avatar
dogmaphobic committed
553

554
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
555
            union_value.param_uint16 = (uint16_t)value.toUInt();
556
            break;
dogmaphobic's avatar
dogmaphobic committed
557

558
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
559
            union_value.param_int16 = (int16_t)value.toInt();
560
            break;
dogmaphobic's avatar
dogmaphobic committed
561

562
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
563
            union_value.param_uint32 = (uint32_t)value.toUInt();
564
            break;
dogmaphobic's avatar
dogmaphobic committed
565

566 567 568
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
dogmaphobic's avatar
dogmaphobic committed
569

570 571 572
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
573

574
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
575
            union_value.param_int32 = (int32_t)value.toInt();
576 577
            break;
    }
dogmaphobic's avatar
dogmaphobic committed
578

579
    p.param_value = union_value.param_float;
580
    p.target_system = (uint8_t)_vehicle->id();
581
    p.target_component = (uint8_t)componentId;
dogmaphobic's avatar
dogmaphobic committed
582

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

585 586
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
587
    _vehicle->sendMessageOnLink(_dedicatedLink, msg);
588 589
}

590
void ParameterLoader::_writeLocalParamCache(int uasId, int componentId)
591
{
592
    MapID2NamedParam cache_map;
593

594 595 596 597
    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()));
598 599
    }

600
    QFile cache_file(parameterCacheFile(uasId, componentId));
601 602 603 604 605 606
    cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate);

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

607 608 609 610 611 612 613
QDir ParameterLoader::parameterCacheDir()
{
    const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
    return spath + QDir::separator() + "ParamCache";
}

QString ParameterLoader::parameterCacheFile(int uasId, int componentId)
614
{
615
    return parameterCacheDir().filePath(QString("%1_%2").arg(uasId).arg(componentId));
616 617
}

618
void ParameterLoader::_tryCacheHashLoad(int uasId, int componentId, QVariant hash_value)
619 620 621
{
    uint32_t crc32_value = 0;
    /* The datastructure of the cache table */
622 623
    MapID2NamedParam cache_map;
    QFile cache_file(parameterCacheFile(uasId, componentId));
624
    if (!cache_file.exists()) {
625
        /* no local cache, just wait for them to come in*/
626 627 628 629 630 631 632 633 634
        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 */
635 636 637 638 639 640 641

    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);
642 643 644
    }

    if (crc32_value == hash_value.toUInt()) {
645
        qCInfo(ParameterLoaderLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
646
        /* if the two param set hashes match, just load from the disk */
647 648 649 650 651 652 653
        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);
654
        }
655 656 657 658 659 660 661 662 663 664 665 666
        // 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);
667 668 669
    }
}

670 671
void ParameterLoader::_saveToEEPROM(void)
{
672 673 674 675 676
    if (_saveRequired) {
        _saveRequired = false;
        if (_vehicle->firmwarePlugin()->isCapable(FirmwarePlugin::MavCmdPreflightStorageCapability)) {
            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);
677
            _vehicle->sendMessageOnLink(_dedicatedLink, msg);
678 679 680 681
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
        } else {
            qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
        }
Don Gagne's avatar
Don Gagne committed
682
    }
683 684
}

685
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
686
{
687
    QString errors;
dogmaphobic's avatar
dogmaphobic committed
688

689 690 691 692 693 694
    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
695 696
                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
697 698
                }

699 700 701 702
                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
703

704
                if (!_autopilot->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
705 706 707 708
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
                    qCDebug(ParameterLoaderLog) << error;
709 710
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
711

712 713
                Fact* fact = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName);
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
714 715 716 717
                    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;
718 719
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
720

721
                qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
Don Gagne's avatar
Don Gagne committed
722
                fact->setRawValue(valStr);
723 724 725
            }
        }
    }
dogmaphobic's avatar
dogmaphobic committed
726

727
    return errors;
728 729
}

730
void ParameterLoader::writeParametersToStream(QTextStream &stream)
731
{
732
    stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
733 734 735 736
    stream << "#\n";
    stream << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    foreach (int componentId, _mapParameterName2Variant.keys()) {
737
        foreach (const QString &paramName, _mapParameterName2Variant[componentId].keys()) {
738 739
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
            Q_ASSERT(fact);
dogmaphobic's avatar
dogmaphobic committed
740

741
            stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueString() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
742 743
        }
    }
dogmaphobic's avatar
dogmaphobic committed
744

745 746 747 748 749 750 751 752
    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
753

754 755
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
dogmaphobic's avatar
dogmaphobic committed
756

757 758
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
dogmaphobic's avatar
dogmaphobic committed
759

760 761
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
dogmaphobic's avatar
dogmaphobic committed
762

763 764
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
dogmaphobic's avatar
dogmaphobic committed
765

766 767
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
dogmaphobic's avatar
dogmaphobic committed
768

769 770 771
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
772

773 774 775 776 777 778 779 780 781 782
        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
783

784 785
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
dogmaphobic's avatar
dogmaphobic committed
786

787 788
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
dogmaphobic's avatar
dogmaphobic committed
789

790 791
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
dogmaphobic's avatar
dogmaphobic committed
792

793 794
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
dogmaphobic's avatar
dogmaphobic committed
795

796 797
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
dogmaphobic's avatar
dogmaphobic committed
798

799 800 801
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
dogmaphobic's avatar
dogmaphobic committed
802

803 804 805 806 807 808 809 810 811
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

void ParameterLoader::_restartWaitingParamTimer(void)
{
    _waitingParamTimeoutTimer.start();
}
812 813 814 815 816 817 818

void ParameterLoader::_checkInitialLoadComplete(void)
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
819

820 821 822 823 824 825
    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
826 827


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

831 832 833 834 835 836 837 838 839 840 841 842 843
    // Check for 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 << ")";
        }
    }
dogmaphobic's avatar
dogmaphobic committed
844

845
    // Check for any errors during vehicle boot
dogmaphobic's avatar
dogmaphobic committed
846

847
    UASMessageHandler* msgHandler = qgcApp()->toolbox()->uasMessageHandler();
848
    if (msgHandler->getErrorCountTotal()) {
849
        QString errors;
850
        bool firstError = true;
851
        bool errorsFound = false;
dogmaphobic's avatar
dogmaphobic committed
852

853 854 855
        msgHandler->lockAccess();
        foreach (UASMessage* msg, msgHandler->messages()) {
            if (msg->severityIsError()) {
856
                if (!firstError) {
dogmaphobic's avatar
dogmaphobic committed
857
                    errors += "<br>";
858 859
                }
                errors += " - ";
860
                errors += msg->getText();
861
                firstError = false;
862
                errorsFound = true;
863 864
            }
        }
865
        msgHandler->showErrorsInToolbar();
866
        msgHandler->unlockAccess();
dogmaphobic's avatar
dogmaphobic committed
867

868
        if (errorsFound) {
dogmaphobic's avatar
dogmaphobic committed
869
            QString errorMsg = QString("<b>Critical safety issue detected:</b><br>%1").arg(errors);
870
            qgcApp()->showMessage(errorMsg);
871
        }
872
    }
dogmaphobic's avatar
dogmaphobic committed
873

874
    // Warn of parameter load failure
dogmaphobic's avatar
dogmaphobic committed
875

876
    if (initialLoadFailures) {
877
        qgcApp()->showMessage("QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
dogmaphobic's avatar
dogmaphobic committed
878
                              "This will cause QGroundControl to be unable to display its full user interface. "
879 880
                              "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.");
881
        qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
882
        emit parametersReady(true);
883 884 885 886 887
    } else {
        // No failed parameters, ok to signal ready
        _parametersReady = true;
        _determineDefaultComponentId();
        _setupGroupMap();
888
        emit parametersReady(false);
889
    }
890
}
891 892 893 894 895 896 897

void ParameterLoader::_initialRequestTimeout(void)
{
    qgcApp()->showMessage("Vehicle did not respond to request for parameters, retrying");
    refreshAllParameters();
    _initialRequestTimeoutTimer.start();
}