ParameterLoader.cc 29.7 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 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.
 
 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.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

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

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

#include <QFile>
#include <QDebug>

QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")

Don Gagne's avatar
Don Gagne committed
40 41
Fact ParameterLoader::_defaultFact;

42
ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
43
    QObject(parent),
44
    _autopilot(autopilot),
45
    _vehicle(vehicle),
46
    _mavlink(MAVLinkProtocol::instance()),
47
    _parametersReady(false),
48
    _initialLoadComplete(false),
49
    _defaultComponentId(FactSystem::defaultComponentId),
50
    _totalParamCount(0)
51
{
52
    Q_ASSERT(_autopilot);
53
    Q_ASSERT(_vehicle);
54
    Q_ASSERT(_mavlink);
55
    
56 57
    // We signal this to ouselves in order to start timer on our thread
    connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer);
58
    
59
    _waitingParamTimeoutTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
60
    _waitingParamTimeoutTimer.setInterval(1000);
61
    connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout);
62
    
63
    // FIXME: Why not direct connect?
64
    connect(_vehicle->uas(), SIGNAL(parameterUpdate(int, int, QString, int, int, int, QVariant)), this, SLOT(_parameterUpdate(int, int, QString, int, int, int, QVariant)));
65
    
66 67
    // Request full param list
    refreshAllParameters();
68 69 70 71 72 73 74 75
}

ParameterLoader::~ParameterLoader()
{

}

/// Called whenever a parameter is updated or first seen.
76
void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
77 78 79 80
{
    bool setMetaData = false;
    
    // Is this for our uas?
81
    if (uasId != _vehicle->id()) {
82 83 84
        return;
    }
    
85 86 87 88 89 90 91 92 93
    qCDebug(ParameterLoaderLog) << "_parameterUpdate (usaId:" << uasId <<
                                    "componentId:" << componentId <<
                                    "name:" << parameterName <<
                                    "count:" << parameterCount <<
                                    "index:" << parameterId <<
                                    "mavType:" << mavType <<
                                    "value:" << value <<
                                    ")";
    
94 95 96 97 98 99 100 101 102
#if 0
    // Handy for testing retry logic
    static int counter = 0;
    if (counter++ & 0x3) {
        qCDebug(ParameterLoaderLog) << "Artificial discard" << counter;
        return;
    }
#endif
    
103 104 105 106 107 108 109 110 111 112 113 114 115
    _dataMutex.lock();
    
    // Restart our waiting for param timer
    _waitingParamTimeoutTimer.start();
    
    // Update our total parameter counts
    if (!_paramCountMap.contains(componentId)) {
        _paramCountMap[componentId] = parameterCount;
        _totalParamCount += parameterCount;
    }
    
    // If we've never seen this component id before, setup the wait lists.
    if (!_waitingReadParamIndexMap.contains(componentId)) {
116 117 118 119
        // 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;
120 121
        }
        
122 123 124
        // The read and write waiting lists for this component are initialized the empty
        _waitingReadParamNameMap[componentId] = QMap<QString, int>();
        _waitingWriteParamNameMap[componentId] = QMap<QString, int>();
125 126 127 128 129
        
        qCDebug(ParameterLoaderLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
    }
    
    // Remove this parameter from the waiting lists
130 131 132
    _waitingReadParamIndexMap[componentId].remove(parameterId);
    _waitingReadParamNameMap[componentId].remove(parameterName);
    _waitingWriteParamNameMap[componentId].remove(parameterName);
133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179
    qCDebug(ParameterLoaderLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
    qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];

    // Track how many parameters we are still waiting for
    
    int waitingReadParamIndexCount = 0;
    int waitingReadParamNameCount = 0;
    int waitingWriteParamNameCount = 0;
	
    foreach(int waitingComponentId, _waitingReadParamIndexMap.keys()) {
        waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
    }
    if (waitingReadParamIndexCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
    }

	
    foreach(int waitingComponentId, _waitingReadParamNameMap.keys()) {
        waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
    }
    if (waitingReadParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
    }
    
    foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
        waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
    }
    if (waitingWriteParamNameCount) {
        qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
    }
    
    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);
    }
    
180 181 182 183 184 185 186 187 188
    // Attempt to determine default component id
    if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) {
        _defaultComponentIdParam = getDefaultComponentIdParam();
    }
    if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
        _defaultComponentId = componentId;
    }
    
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
189
        qCDebug(ParameterLoaderLog) << "Adding new fact";
190 191 192 193 194 195 196
        
        FactMetaData::ValueType_t factType;
        switch (mavType) {
            case MAV_PARAM_TYPE_UINT8:
                factType = FactMetaData::valueTypeUint8;
                break;
            case MAV_PARAM_TYPE_INT8:
197
                factType = FactMetaData::valueTypeInt8;
198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240
                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;
        }
        
        Fact* fact = new Fact(componentId, parameterName, factType, this);
        setMetaData = true;
        
        _mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact);
        
        // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
        connect(fact, &Fact::_containerValueChanged, this, &ParameterLoader::_valueUpdated);
    }
    
    Q_ASSERT(_mapParameterName2Variant[componentId].contains(parameterName));
    
    Fact* fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
    Q_ASSERT(fact);
    fact->_containerSetValue(value);
    
    if (setMetaData) {
        _addMetaDataToFact(fact);
    }
241 242 243 244 245 246 247 248
    
    _dataMutex.unlock();
    
    if (waitingParamCount == 0) {
        // Now that we know vehicle is up to date persist
        _saveToEEPROM();
    }
    
249
    _checkInitialLoadComplete();
250 251 252 253
}

/// Connected to Fact::valueUpdated
///
254
/// Writes the parameter to mavlink, sets up for write wait
255 256 257 258 259 260
void ParameterLoader::_valueUpdated(const QVariant& value)
{
    Fact* fact = qobject_cast<Fact*>(sender());
    Q_ASSERT(fact);
    
    int componentId = fact->componentId();
261
    QString name = fact->name();
262
    
263
    _dataMutex.lock();
264
    
265
    Q_ASSERT(_waitingWriteParamNameMap.contains(componentId));
266 267
    _waitingWriteParamNameMap[componentId].remove(name);    // Remove any old entry
    _waitingWriteParamNameMap[componentId][name] = 0;       // Add new entry and set retry count
268
    _waitingParamTimeoutTimer.start();
269
    
270 271 272 273
    _dataMutex.unlock();
    
    _writeParameterRaw(componentId, fact->name(), value);
    qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
274 275 276 277
}

void ParameterLoader::_addMetaDataToFact(Fact* fact)
{
278 279
    FactMetaData* metaData = new FactMetaData(fact->type(), this);
    fact->setMetaData(metaData);
280 281 282 283
}

void ParameterLoader::refreshAllParameters(void)
{
284 285 286 287
    _dataMutex.lock();
    
    // Reset index wait lists
    foreach (int componentId, _paramCountMap.keys()) {
288 289 290 291
        // Add/Update all indices to the wait list, parameter index is 0-based
        for (int waitingIndex=0; waitingIndex<_paramCountMap[componentId]; waitingIndex++) {
            // This will add a new waiting index if needed and set the retry count for that index to 0
            _waitingReadParamIndexMap[componentId][waitingIndex] = 0;
292 293 294 295 296 297 298 299 300
        }
    }
    
    _dataMutex.unlock();
    
    MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
    Q_ASSERT(mavlink);
    
    mavlink_message_t msg;
301 302
    mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL);
    _vehicle->sendMessage(msg);
303 304
    
    qCDebug(ParameterLoaderLog) << "Request to refresh all parameters";
305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336
}

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!
        
        _defaultComponentId = -1;
        foreach(int componentId, _mapParameterName2Variant.keys()) {
            if (_mapParameterName2Variant[componentId].count() > _defaultComponentId) {
                _defaultComponentId = componentId;
            }
        }
        Q_ASSERT(_defaultComponentId != -1);
    }
}

/// Translates FactSystem::defaultComponentId to real component id if needed
int ParameterLoader::_actualComponentId(int componentId)
{
    if (componentId == FactSystem::defaultComponentId) {
        componentId = _defaultComponentId;
        Q_ASSERT(componentId != FactSystem::defaultComponentId);
    }
    
    return componentId;
}

void ParameterLoader::refreshParameter(int componentId, const QString& name)
{
337 338 339 340 341 342 343 344
    componentId = _actualComponentId(componentId);
    qCDebug(ParameterLoaderLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
    
    _dataMutex.lock();

    Q_ASSERT(_waitingReadParamNameMap.contains(componentId));
    
    if (_waitingReadParamNameMap.contains(componentId)) {
345 346
        _waitingReadParamNameMap[componentId].remove(name); // Remove old wait entry if there
        _waitingReadParamNameMap[componentId][name] = 0;    // Add new wait entry and update retry count
347 348
        emit restartWaitingParamTimer();
    }
349
    
350 351 352
    _dataMutex.unlock();

    _readParameterRaw(componentId, name, -1);
353 354 355 356 357
}

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

360 361 362 363 364 365 366
    foreach(QString name, _mapParameterName2Variant[componentId].keys()) {
        if (name.startsWith(namePrefix)) {
            refreshParameter(componentId, name);
        }
    }
}

367
bool ParameterLoader::parameterExists(int componentId, const QString&  name)
368
{
369 370
    bool ret = false;
    
371 372
    componentId = _actualComponentId(componentId);
    if (_mapParameterName2Variant.contains(componentId)) {
373
        ret = _mapParameterName2Variant[componentId].contains(name);
374
    }
375 376

    return ret;
377 378 379 380 381
}

Fact* ParameterLoader::getFact(int componentId, const QString& name)
{
    componentId = _actualComponentId(componentId);
382 383
    
    if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(name)) {
Don Gagne's avatar
Don Gagne committed
384 385
        qgcApp()->reportMissingParameter(componentId, name);
        return &_defaultFact;
386 387
    }
    
Don Gagne's avatar
Don Gagne committed
388
    return _mapParameterName2Variant[componentId][name].value<Fact*>();
389
}
390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415

QStringList ParameterLoader::parameterNames(void)
{
	QStringList names;
	
	foreach(QString paramName, _mapParameterName2Variant[_defaultComponentId].keys()) {
		names << paramName;
	}
	
	return names;
}

void ParameterLoader::_setupGroupMap(void)
{
    foreach (int componentId, _mapParameterName2Variant.keys()) {
        foreach (QString name, _mapParameterName2Variant[componentId].keys()) {
            Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
            _mapGroup2ParameterName[componentId][fact->group()] += name;
        }
    }
}

const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
    return _mapGroup2ParameterName;
}
416 417 418 419 420 421 422 423 424 425 426

void ParameterLoader::_waitingParamTimeout(void)
{
    bool paramsRequested = false;
    const int maxBatchSize = 10;
    int batchCount = 0;
    
    // We timed out waiting for some parameters from the initial set. Re-request those.
    
    batchCount = 0;
    foreach(int componentId, _waitingReadParamIndexMap.keys()) {
427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442
        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] << ")";
                
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
443 444 445
            }
        }
    }
446 447
    // We need to check for initial load complete here as well, since it could complete on a max retry failure
    _checkInitialLoadComplete();
448 449 450
    
    if (!paramsRequested) {
        foreach(int componentId, _waitingWriteParamNameMap.keys()) {
451
            foreach(QString paramName, _waitingWriteParamNameMap[componentId].keys()) {
452
                paramsRequested = true;
453
                _waitingWriteParamNameMap[componentId][paramName]++;   // Bump retry count
454
                _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->value());
455
                qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
456 457 458 459 460 461 462 463 464 465
                
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
    
    if (!paramsRequested) {
        foreach(int componentId, _waitingReadParamNameMap.keys()) {
466
            foreach(QString paramName, _waitingReadParamNameMap[componentId].keys()) {
467
                paramsRequested = true;
468
                _waitingReadParamNameMap[componentId][paramName]++;   // Bump retry count
469
                _readParameterRaw(componentId, paramName, -1);
470
                qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493
                
                if (++batchCount > maxBatchSize) {
                    goto Out;
                }
            }
        }
    }
	
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
494
                                        _vehicle->id(),             // Target system id
495 496 497
                                        componentId,                // Target component id
                                        fixedParamName,             // Named parameter being requested
                                        paramIndex);                // Parameter index being requested, -1 for named
498
    _vehicle->sendMessage(msg);
499 500 501 502 503 504 505 506 507 508 509 510
}

void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{
    mavlink_param_set_t     p;
    mavlink_param_union_t   union_value;
    
    FactMetaData::ValueType_t factType = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->type();
    p.param_type = _factTypeToMavType(factType);
    
    switch (factType) {
        case FactMetaData::valueTypeUint8:
Don Gagne's avatar
Don Gagne committed
511
            union_value.param_uint8 = (uint8_t)value.toUInt();
512 513 514
            break;
            
        case FactMetaData::valueTypeInt8:
Don Gagne's avatar
Don Gagne committed
515
            union_value.param_int8 = (int8_t)value.toInt();
516 517 518
            break;
            
        case FactMetaData::valueTypeUint16:
Don Gagne's avatar
Don Gagne committed
519
            union_value.param_uint16 = (uint16_t)value.toUInt();
520 521 522
            break;
            
        case FactMetaData::valueTypeInt16:
Don Gagne's avatar
Don Gagne committed
523
            union_value.param_int16 = (int16_t)value.toInt();
524 525 526
            break;
            
        case FactMetaData::valueTypeUint32:
Don Gagne's avatar
Don Gagne committed
527
            union_value.param_uint32 = (uint32_t)value.toUInt();
528 529 530 531 532 533 534 535 536 537 538
            break;
            
        case FactMetaData::valueTypeFloat:
            union_value.param_float = value.toFloat();
            break;
            
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
            
        case FactMetaData::valueTypeInt32:
Don Gagne's avatar
Don Gagne committed
539
            union_value.param_int32 = (int32_t)value.toInt();
540 541 542 543
            break;
    }
    
    p.param_value = union_value.param_float;
544
    p.target_system = (uint8_t)_vehicle->id();
545 546 547 548 549 550
    p.target_component = (uint8_t)componentId;
        
    strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id));
    
    mavlink_message_t msg;
    mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
551
    _vehicle->sendMessage(msg);
552 553 554 555
}

void ParameterLoader::_saveToEEPROM(void)
{
Don Gagne's avatar
Don Gagne committed
556 557 558 559 560 561 562 563
    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);
        _vehicle->sendMessage(msg);
        qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
    } else {
        qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
    }
564 565
}

566
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
567
{
568
    QString errors;
569 570 571 572 573 574 575 576
    bool userWarned = false;
    
    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) {
577
                if (!userWarned && (_vehicle->id() != lineMavId)) {
578 579 580
                    userWarned = true;
                    QString msg("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.");
                    QGCMessageBox::StandardButton button = QGCMessageBox::warning("Parameter Load",
581
                                                                                  msg.arg(lineMavId).arg(_vehicle->id()),
582 583 584
                                                                                  QGCMessageBox::Ok | QGCMessageBox::Cancel,
                                                                                  QGCMessageBox::Cancel);
                    if (button == QGCMessageBox::Cancel) {
585
                        return QString();
586 587 588 589 590 591 592 593 594
                    }
                }   
                
                int     componentId = wpParams.at(1).toInt();
                QString paramName = wpParams.at(2);
                QString valStr = wpParams.at(3);
                uint    mavType = wpParams.at(4).toUInt();
                
                if (!_autopilot->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
595 596 597 598
                    QString error;
                    error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
                    errors += error;
                    qCDebug(ParameterLoaderLog) << error;
599 600 601 602 603
                    continue;
                }
                
                Fact* fact = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName);
                if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
604 605 606 607
                    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;
608 609 610
                    continue;
                }
                
611
                qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
612 613 614 615
                fact->setValue(valStr);
            }
        }
    }
616 617
    
    return errors;
618 619 620 621 622 623 624 625 626 627 628 629 630
}

void ParameterLoader::writeParametersToStream(QTextStream &stream, const QString& name)
{
    stream << "# Onboard parameters for system " << name << "\n";
    stream << "#\n";
    stream << "# MAV ID  COMPONENT ID  PARAM NAME  VALUE (FLOAT)\n";

    foreach (int componentId, _mapParameterName2Variant.keys()) {
        foreach (QString paramName, _mapParameterName2Variant[componentId].keys()) {
            Fact* fact = _mapParameterName2Variant[componentId][paramName].value<Fact*>();
            Q_ASSERT(fact);
            
631
            stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->valueString() << "\t" << QString("%1").arg(_factTypeToMavType(fact->type())) << "\n";
632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701
        }
    }
    
    stream.flush();
}

MAV_PARAM_TYPE ParameterLoader::_factTypeToMavType(FactMetaData::ValueType_t factType)
{
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            return MAV_PARAM_TYPE_UINT8;
            
        case FactMetaData::valueTypeInt8:
            return MAV_PARAM_TYPE_INT8;
            
        case FactMetaData::valueTypeUint16:
            return MAV_PARAM_TYPE_UINT16;
            
        case FactMetaData::valueTypeInt16:
            return MAV_PARAM_TYPE_INT16;
            
        case FactMetaData::valueTypeUint32:
            return MAV_PARAM_TYPE_UINT32;
            
        case FactMetaData::valueTypeFloat:
            return MAV_PARAM_TYPE_REAL32;
            
        default:
            qWarning() << "Unsupported fact type" << factType;
            // fall through
            
        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;
            
        case MAV_PARAM_TYPE_INT8:
            return FactMetaData::valueTypeInt8;
            
        case MAV_PARAM_TYPE_UINT16:
            return FactMetaData::valueTypeUint16;
            
        case MAV_PARAM_TYPE_INT16:
            return FactMetaData::valueTypeInt16;
            
        case MAV_PARAM_TYPE_UINT32:
            return FactMetaData::valueTypeUint32;
            
        case MAV_PARAM_TYPE_REAL32:
            return FactMetaData::valueTypeFloat;
            
        default:
            qWarning() << "Unsupported mav param type" << mavType;
            // fall through
            
        case MAV_PARAM_TYPE_INT32:
            return FactMetaData::valueTypeInt32;
    }
}

void ParameterLoader::_restartWaitingParamTimer(void)
{
    _waitingParamTimeoutTimer.start();
}
702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734

void ParameterLoader::_checkInitialLoadComplete(void)
{
    // Already processed?
    if (_initialLoadComplete) {
        return;
    }
    
    foreach (int componentId, _waitingReadParamIndexMap.keys()) {
        if (_waitingReadParamIndexMap[componentId].count()) {
            // We are still waiting on some parameters, not done yet
            return;
        }
    }
    
    
    // We aren't waiting for any more initial parameter updates, initial parameter loading is complete
    _initialLoadComplete = true;
    
    // 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 << ")";
        }
    }
    
735 736 737
    // Check for any errors during vehicle boot
    
    UASMessageHandler* msgHandler = UASMessageHandler::instance();
738
    if (msgHandler->getErrorCountTotal()) {
739
        QString errors;
740
        bool firstError = true;
741
        bool errorsFound = false;
742 743 744 745
        
        msgHandler->lockAccess();
        foreach (UASMessage* msg, msgHandler->messages()) {
            if (msg->severityIsError()) {
746 747 748 749
                if (!firstError) {
                    errors += "\n";
                }
                errors += " - ";
750
                errors += msg->getText();
751
                firstError = false;
752
                errorsFound = true;
753 754
            }
        }
755
        msgHandler->showErrorsInToolbar();
756 757
        msgHandler->unlockAccess();
        
758
        if (errorsFound) {
759 760 761
            QString errorMsg = QString("Errors were detected during vehicle startup. You should resolve these prior to flight.\n%1").arg(errors);
            qgcApp()->showToolBarMessage(errorMsg);
        }
762 763 764 765
    }
    
    // Warn of parameter load failure
    
766 767
    if (initialLoadFailures) {
        QGCMessageBox::critical("Parameter Load Failure",
768 769 770 771 772 773
                                "QGroundControl was unable to retrieve the full set of parameters from the vehicle. "
                                "This will cause QGroundControl to be unable to display it's 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.");
        qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;

774 775 776 777 778 779 780
    } else {
        // No failed parameters, ok to signal ready
        _parametersReady = true;
        _determineDefaultComponentId();
        _setupGroupMap();
        emit parametersReady();
    }
781
}