QGCCameraControl.cc 48.1 KB
Newer Older
1 2 3 4 5 6 7 8 9
/*!
 * @file
 *   @brief Camera Controller
 *   @author Gus Grubba <mavlink@grubba.com>
 *
 */

#include "QGCCameraControl.h"
#include "QGCCameraIO.h"
Gus Grubba's avatar
Gus Grubba committed
10 11 12 13
#include "SettingsManager.h"
#include "VideoManager.h"
#include "QGCMapEngine.h"

Gus Grubba's avatar
Gus Grubba committed
14
#include <QDir>
Gus Grubba's avatar
Gus Grubba committed
15
#include <QStandardPaths>
16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33
#include <QDomDocument>
#include <QDomNodeList>

QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog")
QGC_LOGGING_CATEGORY(CameraControlLogVerbose, "CameraControlLogVerbose")

static const char* kDefnition       = "definition";
static const char* kParameters      = "parameters";
static const char* kParameter       = "parameter";
static const char* kVersion         = "version";
static const char* kModel           = "model";
static const char* kVendor          = "vendor";
static const char* kLocalization    = "localization";
static const char* kLocale          = "locale";
static const char* kStrings         = "strings";
static const char* kName            = "name";
static const char* kValue           = "value";
static const char* kControl         = "control";
34
static const char* kReadOnly        = "readonly";
35 36 37 38 39 40 41 42 43 44 45 46 47
static const char* kOptions         = "options";
static const char* kOption          = "option";
static const char* kType            = "type";
static const char* kDefault         = "default";
static const char* kDescription     = "description";
static const char* kExclusions      = "exclusions";
static const char* kExclusion       = "exclude";
static const char* kRoption         = "roption";
static const char* kCondition       = "condition";
static const char* kParameterranges = "parameterranges";
static const char* kParameterrange  = "parameterrange";
static const char* kOriginal        = "original";
static const char* kTranslated      = "translated";
48
static const char* kReset           = "reset";
49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115

//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, bool& target)
{
    QDomNamedNodeMap attrs = node.attributes();
    if(!attrs.count()) {
        return false;
    }
    QDomNode subNode = attrs.namedItem(tagName);
    if(subNode.isNull()) {
        return false;
    }
    target = subNode.nodeValue() != "0";
    return true;
}

//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, int& target)
{
    QDomNamedNodeMap attrs = node.attributes();
    if(!attrs.count()) {
        return false;
    }
    QDomNode subNode = attrs.namedItem(tagName);
    if(subNode.isNull()) {
        return false;
    }
    target = subNode.nodeValue().toInt();
    return true;
}

//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, QString& target)
{
    QDomNamedNodeMap attrs = node.attributes();
    if(!attrs.count()) {
        return false;
    }
    QDomNode subNode = attrs.namedItem(tagName);
    if(subNode.isNull()) {
        return false;
    }
    target = subNode.nodeValue();
    return true;
}

//-----------------------------------------------------------------------------
static bool
read_value(QDomNode& element, const char* tagName, QString& target)
{
    QDomElement de = element.firstChildElement(tagName);
    if(de.isNull()) {
        return false;
    }
    target = de.text();
    return true;
}

//-----------------------------------------------------------------------------
QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Vehicle* vehicle, int compID, QObject* parent)
    : FactGroup(0, parent)
    , _vehicle(vehicle)
    , _compID(compID)
    , _version(0)
Gus Grubba's avatar
Gus Grubba committed
116
    , _cached(false)
Gus Grubba's avatar
Gus Grubba committed
117 118 119
    , _storageFree(0)
    , _storageTotal(0)
    , _netManager(NULL)
120
    , _cameraMode(CAM_MODE_UNDEFINED)
Gus Grubba's avatar
Gus Grubba committed
121
    , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED)
122 123
    , _storageInfoRetries(0)
    , _captureInfoRetries(0)
124
{
125
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
126
    memcpy(&_info, info, sizeof(mavlink_camera_information_t));
Gus Grubba's avatar
Gus Grubba committed
127
    connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
128 129 130 131 132 133 134 135
    _vendor = QString((const char*)(void*)&info->vendor_name[0]);
    _modelName = QString((const char*)(void*)&info->model_name[0]);
    int ver = (int)_info.cam_definition_version;
    _cacheFile.sprintf("%s/%s_%s_%03d.xml",
        qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
        _vendor.toStdString().c_str(),
        _modelName.toStdString().c_str(),
        ver);
Gus Grubba's avatar
Gus Grubba committed
136
    if(info->cam_definition_uri[0] != 0) {
Gus Grubba's avatar
Gus Grubba committed
137
        //-- Process camera definition file
Gus Grubba's avatar
Gus Grubba committed
138
        _handleDefinitionFile(info->cam_definition_uri);
Gus Grubba's avatar
Gus Grubba committed
139 140 141
    } else {
        _initWhenReady();
    }
142 143 144 145 146
}

//-----------------------------------------------------------------------------
QGCCameraControl::~QGCCameraControl()
{
Gus Grubba's avatar
Gus Grubba committed
147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
    if(_netManager) {
        delete _netManager;
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_initWhenReady()
{
    qCDebug(CameraControlLog) << "_initWhenReady()";
    if(isBasic()) {
        qCDebug(CameraControlLog) << "Basic, MAVLink only messages.";
        _requestCameraSettings();
    } else {
        _requestAllParameters();
        //-- Give some time to load the parameters before going after the camera settings
        QTimer::singleShot(2000, this, &QGCCameraControl::_requestCameraSettings);
    }
    connect(_vehicle, &Vehicle::mavCommandResult, this, &QGCCameraControl::_mavCommandResult);
    connect(&_captureStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_requestCaptureStatus);
167 168
    connect(&_updateTimer, &QTimer::timeout, this, &QGCCameraControl::_updateTimeout);
    _updateTimer.setSingleShot(true);
Gus Grubba's avatar
Gus Grubba committed
169 170 171 172 173 174 175 176
    _captureStatusTimer.setSingleShot(true);
    QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo);
    _captureStatusTimer.start(2750);
    emit infoChanged();
    if(_netManager) {
        delete _netManager;
        _netManager = NULL;
    }
177 178 179 180 181 182 183 184 185 186 187 188 189 190
}

//-----------------------------------------------------------------------------
QString
QGCCameraControl::firmwareVersion()
{
    int major = (_info.firmware_version >> 24) & 0xFF;
    int minor = (_info.firmware_version >> 16) & 0xFF;
    int build = _info.firmware_version & 0xFFFF;
    QString ver;
    ver.sprintf("%d.%d.%d", major, minor, build);
    return ver;
}

Gus Grubba's avatar
Gus Grubba committed
191 192 193 194 195 196 197 198 199 200 201
//-----------------------------------------------------------------------------
QGCCameraControl::VideoStatus
QGCCameraControl::videoStatus()
{
    return _video_status;
}

//-----------------------------------------------------------------------------
QString
QGCCameraControl::storageFreeStr()
{
202
    return QGCMapEngine::bigSizeToString((quint64)_storageFree * 1024 * 1024);
Gus Grubba's avatar
Gus Grubba committed
203 204
}

205 206 207 208 209
//-----------------------------------------------------------------------------
void
QGCCameraControl::setCameraMode(CameraMode mode)
{
    qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")";
210
    if(mode == CAM_MODE_VIDEO) {
211
        setVideoMode();
212
    } else if(mode == CAM_MODE_PHOTO) {
213 214 215 216 217
        setPhotoMode();
    } else {
        qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode;
        return;
    }
Gus Grubba's avatar
Gus Grubba committed
218 219 220 221 222 223
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_setCameraMode(CameraMode mode)
{
224 225 226 227 228 229 230 231
    _cameraMode = mode;
    emit cameraModeChanged();
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::toggleMode()
{
232
    if(cameraMode() == CAM_MODE_PHOTO) {
233
        setVideoMode();
234
    } else if(cameraMode() == CAM_MODE_VIDEO) {
235 236 237 238 239
        setPhotoMode();
    }
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
240 241
bool
QGCCameraControl::toggleVideo()
242
{
Gus Grubba's avatar
Gus Grubba committed
243 244 245 246 247 248
    if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
        return stopVideo();
    } else {
        return startVideo();
    }
}
249

Gus Grubba's avatar
Gus Grubba committed
250 251 252 253 254 255
//-----------------------------------------------------------------------------
bool
QGCCameraControl::takePhoto()
{
    qCDebug(CameraControlLog) << "takePhoto()";
    //-- Check if camera can capture photos or if it can capture it while in Video Mode
256
    if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode())) {
Gus Grubba's avatar
Gus Grubba committed
257 258 259 260 261 262 263
        return false;
    }
    if(capturesPhotos()) {
        _vehicle->sendMavCommand(
            MAV_COMP_ID_CAMERA,                         // Target component
            MAV_CMD_IMAGE_START_CAPTURE,                // Command id
            false,                                      // ShowError
Gus Grubba's avatar
Gus Grubba committed
264
            0,                                          // Reserved (Set to 0)
Gus Grubba's avatar
Gus Grubba committed
265 266 267 268 269 270 271 272 273 274
            0,                                          // Duration between two consecutive pictures (in seconds--ignored if single image)
            1);                                         // Number of images to capture total - 0 for unlimited capture
        //-- Capture local image as well
        QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
        QDir().mkpath(photoPath);
        photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
        qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath);
        return true;
    }
    return false;
275 276 277
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
278
bool
279 280
QGCCameraControl::startVideo()
{
Gus Grubba's avatar
Gus Grubba committed
281 282
    qCDebug(CameraControlLog) << "startVideo()";
    //-- Check if camera can capture videos or if it can capture it while in Photo Mode
283
    if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) {
Gus Grubba's avatar
Gus Grubba committed
284 285 286 287 288 289 290
        return false;
    }
    if(videoStatus() != VIDEO_CAPTURE_STATUS_RUNNING) {
        _vehicle->sendMavCommand(
            MAV_COMP_ID_CAMERA,                         // Target component
            MAV_CMD_VIDEO_START_CAPTURE,                // Command id
            true,                                       // ShowError
Gus Grubba's avatar
Gus Grubba committed
291
            0,                                          // Reserved (Set to 0)
Gus Grubba's avatar
Gus Grubba committed
292 293 294 295
            0);                                         // CAMERA_CAPTURE_STATUS Frequency
        return true;
    }
    return false;
296 297 298
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
299
bool
300 301
QGCCameraControl::stopVideo()
{
Gus Grubba's avatar
Gus Grubba committed
302 303 304 305 306 307
    qCDebug(CameraControlLog) << "stopVideo()";
    if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
        _vehicle->sendMavCommand(
            MAV_COMP_ID_CAMERA,                         // Target component
            MAV_CMD_VIDEO_STOP_CAPTURE,                 // Command id
            true,                                       // ShowError
Gus Grubba's avatar
Gus Grubba committed
308
            0);                                         // Reserved (Set to 0)
Gus Grubba's avatar
Gus Grubba committed
309 310 311
        return true;
    }
    return false;
312 313 314 315 316 317
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setVideoMode()
{
318
    if(hasModes() && _cameraMode != CAM_MODE_VIDEO) {
319 320 321 322 323 324
        qCDebug(CameraControlLog) << "setVideoMode()";
        //-- Use basic MAVLink message
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_SET_CAMERA_MODE,                // Command id
            true,                                   // ShowError
Gus Grubba's avatar
Gus Grubba committed
325
            0,                                      // Reserved (Set to 0)
326 327
            CAM_MODE_VIDEO);                     // Camera mode (0: photo, 1: video)
        _setCameraMode(CAM_MODE_VIDEO);
328 329 330 331 332 333 334
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoMode()
{
335
    if(hasModes() && _cameraMode != CAM_MODE_PHOTO) {
336 337 338 339 340 341
        qCDebug(CameraControlLog) << "setPhotoMode()";
        //-- Use basic MAVLink message
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_SET_CAMERA_MODE,                // Command id
            true,                                   // ShowError
Gus Grubba's avatar
Gus Grubba committed
342
            0,                                      // Reserved (Set to 0)
343 344
            CAM_MODE_PHOTO);                     // Camera mode (0: photo, 1: video)
        _setCameraMode(CAM_MODE_PHOTO);
345 346 347 348 349 350 351 352
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::resetSettings()
{
    qCDebug(CameraControlLog) << "resetSettings()";
Gus Grubba's avatar
Gus Grubba committed
353 354 355 356 357
    _vehicle->sendMavCommand(
        _compID,                                // Target component
        MAV_CMD_RESET_CAMERA_SETTINGS,          // Command id
        true,                                   // ShowError
        1);                                     // Do Reset
358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::formatCard(int id)
{
    qCDebug(CameraControlLog) << "formatCard()";
    if(_vehicle) {
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_STORAGE_FORMAT,                 // Command id
            true,                                   // ShowError
            id,                                     // Storage ID (1 for first, 2 for second, etc.)
            1);                                     // Do Format
    }
}

Gus Grubba's avatar
Gus Grubba committed
375 376 377 378 379 380 381 382 383 384 385
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestCaptureStatus()
{
    _vehicle->sendMavCommand(
        _compID,                                // target component
        MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS,  // command id
        false,                                  // showError
        1);                                     // Do Request
}

386 387 388 389 390 391 392 393 394
//-----------------------------------------------------------------------------
void
QGCCameraControl::factChanged(Fact* pFact)
{
    _updateActiveList();
    _updateRanges(pFact);
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
395 396
void
QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle)
397
{
Gus Grubba's avatar
Gus Grubba committed
398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418
    //-- Is this ours?
    if(_vehicle->id() != vehicleId || compID() != component) {
        return;
    }
    if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) {
        switch(command) {
            case MAV_CMD_RESET_CAMERA_SETTINGS:
                if(isBasic()) {
                    _requestCameraSettings();
                } else {
                    _requestAllParameters();
                    QTimer::singleShot(2000, this, &QGCCameraControl::_requestCameraSettings);
                }
                break;
            case MAV_CMD_VIDEO_START_CAPTURE:
                _setVideoStatus(VIDEO_CAPTURE_STATUS_RUNNING);
                _captureStatusTimer.start(1000);
                break;
            case MAV_CMD_VIDEO_STOP_CAPTURE:
                _setVideoStatus(VIDEO_CAPTURE_STATUS_STOPPED);
                break;
419 420 421 422 423 424
            case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
                _captureInfoRetries = 0;
                break;
            case MAV_CMD_REQUEST_STORAGE_INFORMATION:
                _storageInfoRetries = 0;
                break;
Gus Grubba's avatar
Gus Grubba committed
425
        }
Gus Grubba's avatar
Gus Grubba committed
426
    } else {
427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450
        if(noReponseFromVehicle || result == MAV_RESULT_TEMPORARILY_REJECTED || result == MAV_RESULT_FAILED) {
            if(noReponseFromVehicle) {
                qCDebug(CameraControlLog) << "No response for" << command;
            } else if (result == MAV_RESULT_TEMPORARILY_REJECTED) {
                qCDebug(CameraControlLog) << "Command temporarily rejected for" << command;
            } else {
                qCDebug(CameraControlLog) << "Command failed for" << command;
            }
            switch(command) {
                case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
                    if(++_captureInfoRetries < 3) {
                        _requestCaptureStatus();
                    } else {
                        qCDebug(CameraControlLog) << "Giving up requesting capture status";
                    }
                    break;
                case MAV_CMD_REQUEST_STORAGE_INFORMATION:
                    if(++_storageInfoRetries < 3) {
                        _requestStorageInfo();
                    } else {
                        qCDebug(CameraControlLog) << "Giving up requesting storage status";
                    }
                    break;
            }
Gus Grubba's avatar
Gus Grubba committed
451
        } else {
452
            qCDebug(CameraControlLog) << "Bad response for" << command << result;
Gus Grubba's avatar
Gus Grubba committed
453
        }
Gus Grubba's avatar
Gus Grubba committed
454 455 456 457 458 459 460 461 462 463
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_setVideoStatus(VideoStatus status)
{
    if(_video_status != status) {
        _video_status = status;
        emit videoStatusChanged();
464
    }
Gus Grubba's avatar
Gus Grubba committed
465 466 467 468 469 470
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
{
Gus Grubba's avatar
Gus Grubba committed
471
    QByteArray originalData(bytes);
472 473 474 475 476 477 478 479 480 481 482 483 484 485 486
    //-- Handle localization
    if(!_handleLocalization(bytes)) {
        return false;
    }
    int errorLine;
    QString errorMsg;
    QDomDocument doc;
    if(!doc.setContent(bytes, false, &errorMsg, &errorLine)) {
        qCritical() << "Unable to parse camera definition file on line:" << errorLine;
        qCritical() << errorMsg;
        return false;
    }
    //-- Load camera constants
    QDomNodeList defElements = doc.elementsByTagName(kDefnition);
    if(!defElements.size() || !_loadConstants(defElements)) {
Gus Grubba's avatar
Gus Grubba committed
487
        qWarning() <<  "Unable to load camera constants from camera definition";
488 489 490 491 492
        return false;
    }
    //-- Load camera parameters
    QDomNodeList paramElements = doc.elementsByTagName(kParameters);
    if(!paramElements.size() || !_loadSettings(paramElements)) {
Gus Grubba's avatar
Gus Grubba committed
493
        qWarning() <<  "Unable to load camera parameters from camera definition";
494 495
        return false;
    }
Gus Grubba's avatar
Gus Grubba committed
496 497
    //-- If this is new, cache it
    if(!_cached) {
498 499
        qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile;
        QFile file(_cacheFile);
Gus Grubba's avatar
Gus Grubba committed
500
        if (!file.open(QIODevice::WriteOnly)) {
501
            qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString());
Gus Grubba's avatar
Gus Grubba committed
502 503 504 505
        } else {
            file.write(originalData);
        }
    }
506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557
    return true;
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadConstants(const QDomNodeList nodeList)
{
    QDomNode node = nodeList.item(0);
    if(!read_attribute(node, kVersion, _version)) {
        return false;
    }
    if(!read_value(node, kModel, _modelName)) {
        return false;
    }
    if(!read_value(node, kVendor, _vendor)) {
        return false;
    }
    return true;
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
{
    QDomNode node = nodeList.item(0);
    QDomElement elem = node.toElement();
    QDomNodeList parameters = elem.elementsByTagName(kParameter);
    //-- Pre-process settings (maintain order and skip non-controls)
    for(int i = 0; i < parameters.size(); i++) {
        QDomNode parameterNode = parameters.item(i);
        QString name;
        if(read_attribute(parameterNode, kName, name)) {
            bool control = true;
            read_attribute(parameterNode, kControl, control);
            if(control) {
                _settings << name;
            }
        } else {
            qCritical() << "Parameter entry missing parameter name";
            return false;
        }
    }
    //-- Load parameters
    for(int i = 0; i < parameters.size(); i++) {
        QDomNode parameterNode = parameters.item(i);
        QString factName;
        read_attribute(parameterNode, kName, factName);
        QString type;
        if(!read_attribute(parameterNode, kType, type)) {
            qCritical() << QString("Parameter %1 missing parameter type").arg(factName);
            return false;
        }
558 559 560 561 562 563 564
        //-- Does it have a control?
        bool control = true;
        read_attribute(parameterNode, kControl, control);
        //-- Is it read only?
        bool readOnly = false;
        read_attribute(parameterNode, kReadOnly, readOnly);
        //-- Param type
565 566 567 568 569 570
        bool unknownType;
        FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
        if (unknownType) {
            qCritical() << QString("Unknown type for parameter %1").arg(factName);
            return false;
        }
571
        //-- Description
572 573 574 575 576
        QString description;
        if(!read_value(parameterNode, kDescription, description)) {
            qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
            return false;
        }
577 578 579 580 581 582
        //-- Does it require full update on changes?
        bool update = false;
        read_attribute(parameterNode, kReset, update);
        if(update) {
            _requestUpdates << factName;
        }
583 584
        //-- Build metadata
        FactMetaData* metaData = new FactMetaData(factType, factName, this);
585
        QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
586 587
        metaData->setShortDescription(description);
        metaData->setLongDescription(description);
588 589
        metaData->setHasControl(control);
        metaData->setReadOnly(readOnly);
590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614
        //-- Options (enums)
        QDomElement optionElem = parameterNode.toElement();
        QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions);
        if(optionsRoot.size()) {
            //-- Iterate options
            QDomNode node = optionsRoot.item(0);
            QDomElement elem = node.toElement();
            QDomNodeList options = elem.elementsByTagName(kOption);
            for(int i = 0; i < options.size(); i++) {
                QDomNode option = options.item(i);
                QString optName;
                QString optValue;
                QVariant optVariant;
                if(!_loadNameValue(option, factName, metaData, optName, optValue, optVariant)) {
                    delete metaData;
                    return false;
                }
                metaData->addEnumInfo(optName, optVariant);
                _originalOptNames[factName]  << optName;
                _originalOptValues[factName] << optVariant;
                //-- Check for exclusions
                QStringList exclusions = _loadExclusions(option);
                if(exclusions.size()) {
                    qCDebug(CameraControlLogVerbose) << "New exclusions:" << factName << optValue << exclusions;
                    QGCCameraOptionExclusion* pExc = new QGCCameraOptionExclusion(this, factName, optValue, exclusions);
615
                    QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644
                    _valueExclusions.append(pExc);
                }
                //-- Check for range rules
                if(!_loadRanges(option, factName, optValue)) {
                    delete metaData;
                    return false;
                }
            }
        }
        QString defaultValue;
        if(read_attribute(parameterNode, kDefault, defaultValue)) {
            QVariant defaultVariant;
            QString  errorString;
            if (metaData->convertAndValidateRaw(defaultValue, false, defaultVariant, errorString)) {
                metaData->setRawDefaultValue(defaultVariant);
            } else {
                qWarning() << "Invalid default value for" << factName
                           << " type:"  << metaData->type()
                           << " value:" << defaultValue
                           << " error:" << errorString;
            }
        }
        //-- Set metadata and Fact
        if (_nameToFactMetaDataMap.contains(factName)) {
            qWarning() << QStringLiteral("Duplicate fact name:") << factName;
            delete metaData;
        } else {
            _nameToFactMetaDataMap[factName] = metaData;
            Fact* pFact = new Fact(_compID, factName, factType, this);
645
            QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
646
            pFact->setMetaData(metaData);
Gus Grubba's avatar
Gus Grubba committed
647
            pFact->_containerSetRawValue(metaData->rawDefaultValue());
648
            QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle);
649
            QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership);
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 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 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752
            _paramIO[factName] = pIO;
            _addFact(pFact, factName);
        }
    }
    if(_nameToFactMetaDataMap.size() > 0) {
        _addFactGroup(this, "camera");
        _processRanges();
        _activeSettings = _settings;
        emit activeSettingsChanged();
        return true;
    }
    return false;
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_handleLocalization(QByteArray& bytes)
{
    QString errorMsg;
    int errorLine;
    QDomDocument doc;
    if(!doc.setContent(bytes, false, &errorMsg, &errorLine)) {
        qCritical() << "Unable to parse camera definition file on line:" << errorLine;
        qCritical() << errorMsg;
        return false;
    }
    //-- Find out where we are
    QLocale locale = QLocale::system();
#if defined (__macos__)
    locale = QLocale(locale.name());
#endif
    QString localeName = locale.name().toLower().replace("-", "_");
    qCDebug(CameraControlLog) << "Current locale:" << localeName;
    if(localeName == "en_us") {
        // Nothing to do
        return true;
    }
    QDomNodeList locRoot = doc.elementsByTagName(kLocalization);
    if(!locRoot.size()) {
        // Nothing to do
        return true;
    }
    //-- Iterate locales
    QDomNode node = locRoot.item(0);
    QDomElement elem = node.toElement();
    QDomNodeList locales = elem.elementsByTagName(kLocale);
    for(int i = 0; i < locales.size(); i++) {
        QDomNode locale = locales.item(i);
        QString name;
        if(!read_attribute(locale, kName, name)) {
            qWarning() << "Localization entry is missing its name attribute";
            continue;
        }
        // If we found a direct match, deal with it now
        if(localeName == name.toLower().replace("-", "_")) {
            return _replaceLocaleStrings(locale, bytes);
        }
    }
    //-- No direct match. Pick first matching language (if any)
    localeName = localeName.left(3);
    for(int i = 0; i < locales.size(); i++) {
        QDomNode locale = locales.item(i);
        QString name;
        read_attribute(locale, kName, name);
        if(name.toLower().startsWith(localeName)) {
            return _replaceLocaleStrings(locale, bytes);
        }
    }
    //-- Could not find a language to use
    qWarning() <<  "No match for" << QLocale::system().name() << "in camera definition file";
    //-- Just use default, en_US
    return true;
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_replaceLocaleStrings(const QDomNode node, QByteArray& bytes)
{
    QDomElement stringElem = node.toElement();
    QDomNodeList strings = stringElem.elementsByTagName(kStrings);
    for(int i = 0; i < strings.size(); i++) {
        QDomNode stringNode = strings.item(i);
        QString original;
        QString translated;
        if(read_attribute(stringNode, kOriginal, original)) {
            if(read_attribute(stringNode, kTranslated, translated)) {
                QString o; o = "\"" + original + "\"";
                QString t; t = "\"" + translated + "\"";
                bytes.replace(o.toUtf8(), t.toUtf8());
                o = ">" + original + "<";
                t = ">" + translated + "<";
                bytes.replace(o.toUtf8(), t.toUtf8());
            }
        }
    }
    return true;
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestAllParameters()
{
    //-- Reset receive list
753 754 755 756 757 758
    foreach(QString paramName, _paramIO.keys()) {
        if(_paramIO[paramName]) {
            _paramIO[paramName]->setParamRequest();
        } else {
            qCritical() << "QGCParamIO is NULL" << paramName;
        }
759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790
    }
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    mavlink_message_t msg;
    mavlink_msg_param_ext_request_list_pack_chan(
        mavlink->getSystemId(),
        mavlink->getComponentId(),
        _vehicle->priorityLink()->mavlinkChannel(),
        &msg,
        _vehicle->id(),
        compID());
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    qCDebug(CameraControlLogVerbose) << "Request all parameters";
}

//-----------------------------------------------------------------------------
QString
QGCCameraControl::_getParamName(const char* param_id)
{
    QByteArray bytes(param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
    QString parameterName(bytes);
    return parameterName;
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::handleParamAck(const mavlink_param_ext_ack_t& ack)
{
    QString paramName = _getParamName(ack.param_id);
    if(!_paramIO.contains(paramName)) {
        qCWarning(CameraControlLog) << "Received PARAM_EXT_ACK for unknown param:" << paramName;
        return;
    }
791 792 793 794 795
    if(_paramIO[paramName]) {
        _paramIO[paramName]->handleParamAck(ack);
    } else {
        qCritical() << "QGCParamIO is NULL" << paramName;
    }
796 797 798 799 800 801 802 803 804 805 806
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::handleParamValue(const mavlink_param_ext_value_t& value)
{
    QString paramName = _getParamName(value.param_id);
    if(!_paramIO.contains(paramName)) {
        qCWarning(CameraControlLog) << "Received PARAM_EXT_VALUE for unknown param:" << paramName;
        return;
    }
807 808 809 810 811
    if(_paramIO[paramName]) {
        _paramIO[paramName]->handleParamValue(value);
    } else {
        qCritical() << "QGCParamIO is NULL" << paramName;
    }
812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_updateActiveList()
{
    //-- Clear out excluded parameters based on exclusion rules
    QStringList exclusionList;
    foreach(QGCCameraOptionExclusion* param, _valueExclusions) {
        Fact* pFact = getFact(param->param);
        if(pFact) {
            QString option = pFact->rawValueString();
            if(param->value == option) {
                exclusionList << param->exclusions;
            }
        }
    }
829
    QStringList active;
830 831
    foreach(QString key, _settings) {
        if(!exclusionList.contains(key)) {
832
            active.append(key);
833 834
        }
    }
835 836 837 838 839
    if(active != _activeSettings) {
        qCDebug(CameraControlLogVerbose) << "Excluding" << exclusionList;
        _activeSettings = active;
        emit activeSettingsChanged();
    }
840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_processConditionTest(const QString conditionTest)
{
    enum {
        TEST_NONE,
        TEST_EQUAL,
        TEST_NOT_EQUAL,
        TEST_GREATER,
        TEST_SMALLER
    };
    qCDebug(CameraControlLogVerbose) << "_processConditionTest(" << conditionTest << ")";
    int op = TEST_NONE;
    QStringList test;
    if(conditionTest.contains("!=")) {
        test = conditionTest.split("!=", QString::SkipEmptyParts);
        op = TEST_NOT_EQUAL;
    } else if(conditionTest.contains("=")) {
        test = conditionTest.split("=", QString::SkipEmptyParts);
        op = TEST_EQUAL;
    } else if(conditionTest.contains(">")) {
        test = conditionTest.split(">", QString::SkipEmptyParts);
        op = TEST_GREATER;
    } else if(conditionTest.contains("<")) {
        test = conditionTest.split("<", QString::SkipEmptyParts);
        op = TEST_SMALLER;
    }
    if(test.size() == 2) {
        Fact* pFact = getFact(test[0]);
        if(pFact) {
            switch(op) {
            case TEST_EQUAL:
                return pFact->rawValueString() == test[1];
            case TEST_NOT_EQUAL:
                return pFact->rawValueString() != test[1];
            case TEST_GREATER:
                return pFact->rawValueString() > test[1];
            case TEST_SMALLER:
                return pFact->rawValueString() < test[1];
            case TEST_NONE:
                break;
            }
        } else {
            qWarning() << "Invalid condition parameter:" << test[0] << "in" << conditionTest;
            return false;
        }
    }
    qWarning() << "Invalid condition" << conditionTest;
    return false;
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_processCondition(const QString condition)
{
    qCDebug(CameraControlLogVerbose) << "_processCondition(" << condition << ")";
    bool result = true;
    bool andOp  = true;
    if(!condition.isEmpty()) {
        QStringList scond = condition.split(" ", QString::SkipEmptyParts);
        while(scond.size()) {
            QString test = scond.first();
            scond.removeFirst();
            if(andOp) {
                result = result && _processConditionTest(test);
            } else {
                result = result || _processConditionTest(test);
            }
            if(!scond.size()) {
                return result;
            }
            andOp = scond.first().toUpper() == "AND";
            scond.removeFirst();
        }
    }
    return result;
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_updateRanges(Fact* pFact)
{
924 925
    QMap<Fact*, QGCCameraOptionRange*> rangesSet;
    QMap<Fact*, QString> rangesReset;
926 927
    QStringList changedList;
    QStringList resetList;
928
    //-- Iterate range sets looking for limited ranges
929 930 931 932 933 934
    foreach(QGCCameraOptionRange* pRange, _optionRanges) {
        //-- If this fact or one of its conditions is part of this range set
        if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
            Fact* pRFact = getFact(pRange->param);          //-- This parameter
            Fact* pTFact = getFact(pRange->targetParam);    //-- The target parameter (the one its range is to change)
            if(pRFact && pTFact) {
935
                //qCDebug(CameraControlLogVerbose) << "Check new set of options for" << pTFact->name();
936 937
                QString option = pRFact->rawValueString();  //-- This parameter value
                //-- If this value (and condition) triggers a change in the target range
938
                //qCDebug(CameraControlLogVerbose) << "Range value:" << pRange->value << "Current value:" << option << "Condition:" << pRange->condition;
939
                if(pRange->value == option && _processCondition(pRange->condition)) {
940
                    if(pTFact->enumStrings() != pRange->optNames) {
941 942
                        //-- Set limited range set
                        rangesSet[pTFact] = pRange;
943
                        qCDebug(CameraControlLogVerbose) << "Limited set of options for:" << pRange->targetParam << pRange->optNames;
944
                    }
945
                    changedList << pRange->targetParam;
946 947 948 949 950 951 952 953 954 955 956 957
                }
            }
        }
    }
    //-- Iterate range sets again looking for resets
    foreach(QGCCameraOptionRange* pRange, _optionRanges) {
        if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
            Fact* pTFact = getFact(pRange->targetParam);    //-- The target parameter (the one its range is to change)
            if(!resetList.contains(pRange->targetParam)) {
                if(pTFact->enumStrings() != _originalOptNames[pRange->targetParam]) {
                    //-- Restore full option set
                    rangesReset[pTFact] = pRange->targetParam;
958
                    qCDebug(CameraControlLogVerbose) << "Restore full set of options for:" << pRange->targetParam << _originalOptNames[pRange->targetParam];
959
                }
960
                resetList << pRange->targetParam;
961 962 963
            }
        }
    }
964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981
    //-- Update limited range set
    foreach (Fact* pFact, rangesSet.keys()) {
        pFact->setEnumInfo(rangesSet[pFact]->optNames, rangesSet[pFact]->optVariants);
        if(!_updates.contains(pFact)) {
            _paramIO[pFact->name()]->optNames = rangesSet[pFact]->optNames;
            _paramIO[pFact->name()]->optVariants = rangesSet[pFact]->optVariants;
            _updates << pFact;
        }
    }
    //-- Restore full range set
    foreach (Fact* pFact, rangesReset.keys()) {
        pFact->setEnumInfo(_originalOptNames[rangesReset[pFact]], _originalOptValues[rangesReset[pFact]]);
        if(!_updates.contains(pFact)) {
            _paramIO[pFact->name()]->optNames = _originalOptNames[rangesReset[pFact]];
            _paramIO[pFact->name()]->optVariants = _originalOptValues[rangesReset[pFact]];
            _updates << pFact;
        }
    }
982 983
    //-- Parameter update requests
    if(_requestUpdates.contains(pFact->name())) {
984
        QTimer::singleShot(250, this, &QGCCameraControl::_requestAllParameters);
985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002
    }
    //-- Update UI (Asynchronous state where values come back after a while)
    if(_updates.size()) {
        _updateTimer.start(500);
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_updateTimeout()
{
    //-- Update UI
    foreach (Fact* pFact, _updates) {
        pFact->setEnumInfo(_paramIO[pFact->name()]->optNames, _paramIO[pFact->name()]->optVariants);
        qCDebug(CameraControlLogVerbose) << "Update enums" << pFact->name() << pFact->enumStrings();
        emit pFact->enumsChanged();
    }
    _updates.clear();
1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestCameraSettings()
{
    qCDebug(CameraControlLog) << "_requestCameraSettings()";
    if(_vehicle) {
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_REQUEST_CAMERA_SETTINGS,        // command id
            false,                                  // showError
            1);                                     // Do Request
    }
}

Gus Grubba's avatar
Gus Grubba committed
1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStorageInfo()
{
    qCDebug(CameraControlLog) << "_requestStorageInfo()";
    if(_vehicle) {
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_REQUEST_STORAGE_INFORMATION,    // command id
            false,                                  // showError
            0,                                      // Storage ID (0 for all, 1 for first, 2 for second, etc.)
            1);                                     // Do Request
    }
}

1034 1035 1036 1037
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
{
Gus Grubba's avatar
Gus Grubba committed
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
    qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id;
    _setCameraMode((CameraMode)settings.mode_id);
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st)
{
    qCDebug(CameraControlLog) << "_handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity;
    if(_storageTotal != st.total_capacity) {
        _storageTotal = st.total_capacity;
    }
    //-- Always emit this
    emit storageTotalChanged();
    if(_storageFree != st.available_capacity) {
        _storageFree = st.available_capacity;
        emit storageFreeChanged();
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap)
{
    //-- This is a response to MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
    qCDebug(CameraControlLog) << "handleCaptureStatus:" << cap.available_capacity << cap.image_interval << cap.image_status << cap.recording_time_ms << cap.video_status;
    //-- Disk Free Space
    if(_storageFree != cap.available_capacity) {
        _storageFree = cap.available_capacity;
        emit storageFreeChanged();
    }
    //-- Video Capture Status
    _setVideoStatus((VideoStatus)cap.video_status);
    //-- Keep asking for it once in a while when recording
    if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
        _captureStatusTimer.start(5000);
    }
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 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
}

//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadExclusions(QDomNode option)
{
    QStringList exclusionList;
    QDomElement optionElem = option.toElement();
    QDomNodeList excRoot = optionElem.elementsByTagName(kExclusions);
    if(excRoot.size()) {
        //-- Iterate options
        QDomNode node = excRoot.item(0);
        QDomElement elem = node.toElement();
        QDomNodeList exclusions = elem.elementsByTagName(kExclusion);
        for(int i = 0; i < exclusions.size(); i++) {
            QString exclude = exclusions.item(i).toElement().text();
            if(!exclude.isEmpty()) {
                exclusionList << exclude;
            }
        }
    }
    return exclusionList;
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadRanges(QDomNode option, const QString factName, QString paramValue)
{
    QDomElement optionElem = option.toElement();
    QDomNodeList rangeRoot = optionElem.elementsByTagName(kParameterranges);
    if(rangeRoot.size()) {
        QDomNode node = rangeRoot.item(0);
        QDomElement elem = node.toElement();
        QDomNodeList parameterRanges = elem.elementsByTagName(kParameterrange);
        //-- Iterate parameter ranges
        for(int i = 0; i < parameterRanges.size(); i++) {
            QString param;
            QString condition;
            QMap<QString, QVariant> rangeList;
            QDomNode paramRange = parameterRanges.item(i);
            if(!read_attribute(paramRange, kParameter, param)) {
                qCritical() << QString("Malformed option range for parameter %1").arg(factName);
                return false;
            }
            read_attribute(paramRange, kCondition, condition);
            QDomElement pelem = paramRange.toElement();
            QDomNodeList rangeOptions = pelem.elementsByTagName(kRoption);
            QStringList  optNames;
            QStringList  optValues;
            //-- Iterate options
            for(int i = 0; i < rangeOptions.size(); i++) {
                QString optName;
                QString optValue;
                QDomNode roption = rangeOptions.item(i);
                if(!read_attribute(roption, kName, optName)) {
                    qCritical() << QString("Malformed roption for parameter %1").arg(factName);
                    return false;
                }
                if(!read_attribute(roption, kValue, optValue)) {
                    qCritical() << QString("Malformed rvalue for parameter %1").arg(factName);
                    return false;
                }
                optNames  << optName;
                optValues << optValue;
            }
            if(optNames.size()) {
                QGCCameraOptionRange* pRange = new QGCCameraOptionRange(this, factName, paramValue, param, condition, optNames, optValues);
                _optionRanges.append(pRange);
                qCDebug(CameraControlLogVerbose) << "New range limit:" << factName << paramValue << param << condition << optNames << optValues;
            }
        }
    }
    return true;
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_processRanges()
{
    //-- After all parameter are loaded, process parameter ranges
    foreach(QGCCameraOptionRange* pRange, _optionRanges) {
        Fact* pRFact = getFact(pRange->targetParam);
        if(pRFact) {
            for(int i = 0; i < pRange->optNames.size(); i++) {
                QVariant optVariant;
                QString  errorString;
                if (!pRFact->metaData()->convertAndValidateRaw(pRange->optValues[i], false, optVariant, errorString)) {
                    qWarning() << "Invalid roption value, name:" << pRange->targetParam
                               << " type:"  << pRFact->metaData()->type()
                               << " value:" << pRange->optValues[i]
                               << " error:" << errorString;
                } else {
                    pRange->optVariants << optVariant;
                }
            }
        }
    }
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant)
{
    if(!read_attribute(option, kName, optName)) {
        qCritical() << QString("Malformed option for parameter %1").arg(factName);
        return false;
    }
    if(!read_attribute(option, kValue, optValue)) {
        qCritical() << QString("Malformed value for parameter %1").arg(factName);
        return false;
    }
    QString  errorString;
    if (!metaData->convertAndValidateRaw(optValue, false, optVariant, errorString)) {
        qWarning() << "Invalid option value, name:" << factName
                   << " type:"  << metaData->type()
                   << " value:" << optValue
                   << " error:" << errorString;
    }
    return true;
}
Gus Grubba's avatar
Gus Grubba committed
1195

Gus Grubba's avatar
Gus Grubba committed
1196 1197 1198 1199 1200
//-----------------------------------------------------------------------------
void
QGCCameraControl::_handleDefinitionFile(const QString &url)
{
    //-- First check and see if we have it cached
1201
    QFile xmlFile(_cacheFile);
Gus Grubba's avatar
Gus Grubba committed
1202 1203 1204 1205 1206 1207
    if (!xmlFile.exists()) {
        qCDebug(CameraControlLog) << "No camera definition file cached";
        _httpRequest(url);
        return;
    }
    if (!xmlFile.open(QIODevice::ReadOnly)) {
1208
        qWarning() << "Could not read cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1209 1210 1211 1212 1213 1214
        _httpRequest(url);
        return;
    }
    QByteArray bytes = xmlFile.readAll();
    QDomDocument doc;
    if(!doc.setContent(bytes, false)) {
1215
        qWarning() << "Could not parse cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1216 1217 1218 1219
        _httpRequest(url);
        return;
    }
    //-- We have it
1220
    qCDebug(CameraControlLog) << "Using cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1221 1222 1223 1224
    _cached = true;
    emit dataReady(bytes);
}

Gus Grubba's avatar
Gus Grubba committed
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
//-----------------------------------------------------------------------------
void
QGCCameraControl::_httpRequest(const QString &url)
{
    qCDebug(CameraControlLog) << "Request camera definition:" << url;
    if(!_netManager) {
        _netManager = new QNetworkAccessManager(this);
    }
    QNetworkProxy savedProxy = _netManager->proxy();
    QNetworkProxy tempProxy;
    tempProxy.setType(QNetworkProxy::DefaultProxy);
    _netManager->setProxy(tempProxy);
    QNetworkRequest request(url);
    request.setAttribute(QNetworkRequest::FollowRedirectsAttribute, true);
    QSslConfiguration conf = request.sslConfiguration();
    conf.setPeerVerifyMode(QSslSocket::VerifyNone);
    request.setSslConfiguration(conf);
    QNetworkReply* reply = _netManager->get(request);
    connect(reply, &QNetworkReply::finished,  this, &QGCCameraControl::_downloadFinished);
    _netManager->setProxy(savedProxy);
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_downloadFinished()
{
    QNetworkReply* reply = qobject_cast<QNetworkReply*>(sender());
    if(!reply) {
        return;
    }
    int err = reply->error();
    int http_code = reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toInt();
    QByteArray data = reply->readAll();
    if(err == QNetworkReply::NoError && http_code == 200) {
        data.append("\n");
    } else {
        data.clear();
        qWarning() << QString("Camera Definition download error: %1 status: %2").arg(reply->errorString(), reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toString());
    }
    emit dataReady(data);
    //reply->deleteLater();
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_dataReady(QByteArray data)
{
    if(data.size()) {
        qCDebug(CameraControlLog) << "Parsing camera definition";
        _loadCameraDefinitionFile(data);
1275 1276
    } else {
        qCDebug(CameraControlLog) << "No camera definition";
Gus Grubba's avatar
Gus Grubba committed
1277 1278 1279
    }
    _initWhenReady();
}
1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290

//-----------------------------------------------------------------------------
void
QGCCameraControl::_paramDone()
{
    foreach(QString param, _paramIO.keys()) {
        if(!_paramIO[param]->paramDone()) {
            return;
        }
    }
    //-- All parameters loaded (or timed out)
Gus Grubba's avatar
Gus Grubba committed
1291
    emit parametersReady();
1292
}
1293 1294 1295 1296 1297 1298 1299 1300 1301

//-----------------------------------------------------------------------------
bool
QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue)
{
    Q_UNUSED(pFact);
    Q_UNUSED(newValue);
    return true;
}