QGCCameraControl.cc 57.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
#include <QDomDocument>
#include <QDomNodeList>

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

22
static const char* kCondition       = "condition";
23 24
static const char* kControl         = "control";
static const char* kDefault         = "default";
25
static const char* kDefnition       = "definition";
26 27
static const char* kDescription     = "description";
static const char* kExclusion       = "exclude";
28 29 30
static const char* kExclusions      = "exclusions";
static const char* kLocale          = "locale";
static const char* kLocalization    = "localization";
31 32
static const char* kMax             = "max";
static const char* kMin             = "min";
33 34 35 36
static const char* kModel           = "model";
static const char* kName            = "name";
static const char* kOption          = "option";
static const char* kOptions         = "options";
37
static const char* kOriginal        = "original";
38 39 40 41 42
static const char* kParameter       = "parameter";
static const char* kParameterrange  = "parameterrange";
static const char* kParameterranges = "parameterranges";
static const char* kParameters      = "parameters";
static const char* kReadOnly        = "readonly";
43
static const char* kWriteOnly       = "writeonly";
44
static const char* kRoption         = "roption";
45
static const char* kStep            = "step";
46
static const char* kStrings         = "strings";
47
static const char* kTranslated      = "translated";
48
static const char* kType            = "type";
49
static const char* kUnit            = "unit";
50 51 52 53 54
static const char* kUpdate          = "update";
static const char* kUpdates         = "updates";
static const char* kValue           = "value";
static const char* kVendor          = "vendor";
static const char* kVersion         = "version";
55

56 57 58 59
static const char* kPhotoMode       = "PhotoMode";
static const char* kPhotoLapse      = "PhotoLapse";
static const char* kPhotoLapseCount = "PhotoLapseCount";

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 116 117 118 119 120 121 122 123 124 125
//-----------------------------------------------------------------------------
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
126
    , _cached(false)
Gus Grubba's avatar
Gus Grubba committed
127 128 129
    , _storageFree(0)
    , _storageTotal(0)
    , _netManager(NULL)
130
    , _cameraMode(CAM_MODE_UNDEFINED)
131 132 133
    , _photoMode(PHOTO_CAPTURE_SINGLE)
    , _photoLapse(1.0)
    , _photoLapseCount(0)
Gus Grubba's avatar
Gus Grubba committed
134
    , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED)
135
    , _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED)
136 137
    , _storageInfoRetries(0)
    , _captureInfoRetries(0)
138
{
139
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
140
    memcpy(&_info, info, sizeof(mavlink_camera_information_t));
Gus Grubba's avatar
Gus Grubba committed
141
    connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
142 143 144 145 146 147 148 149
    _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
150
    if(info->cam_definition_uri[0] != 0) {
Gus Grubba's avatar
Gus Grubba committed
151
        //-- Process camera definition file
Gus Grubba's avatar
Gus Grubba committed
152
        _handleDefinitionFile(info->cam_definition_uri);
Gus Grubba's avatar
Gus Grubba committed
153 154 155
    } else {
        _initWhenReady();
    }
156 157 158 159
    QSettings settings;
    _photoMode = (PhotoMode)settings.value(kPhotoMode, (int)PHOTO_CAPTURE_SINGLE).toInt();
    _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
    _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
160 161 162 163 164
}

//-----------------------------------------------------------------------------
QGCCameraControl::~QGCCameraControl()
{
Gus Grubba's avatar
Gus Grubba committed
165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192
    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);
    _captureStatusTimer.setSingleShot(true);
    QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo);
    _captureStatusTimer.start(2750);
    emit infoChanged();
    if(_netManager) {
        delete _netManager;
        _netManager = NULL;
    }
193 194 195 196 197 198 199 200 201 202 203 204 205 206
}

//-----------------------------------------------------------------------------
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
207 208 209 210 211 212 213
//-----------------------------------------------------------------------------
QGCCameraControl::VideoStatus
QGCCameraControl::videoStatus()
{
    return _video_status;
}

214 215 216 217 218 219 220
//-----------------------------------------------------------------------------
QGCCameraControl::PhotoStatus
QGCCameraControl::photoStatus()
{
    return _photo_status;
}

Gus Grubba's avatar
Gus Grubba committed
221 222 223 224
//-----------------------------------------------------------------------------
QString
QGCCameraControl::storageFreeStr()
{
225
    return QGCMapEngine::bigSizeToString((quint64)_storageFree * 1024 * 1024);
Gus Grubba's avatar
Gus Grubba committed
226 227
}

228 229 230 231 232
//-----------------------------------------------------------------------------
void
QGCCameraControl::setCameraMode(CameraMode mode)
{
    qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")";
233
    if(mode == CAM_MODE_VIDEO) {
234
        setVideoMode();
235
    } else if(mode == CAM_MODE_PHOTO) {
236 237 238 239 240
        setPhotoMode();
    } else {
        qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode;
        return;
    }
Gus Grubba's avatar
Gus Grubba committed
241 242
}

243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272
//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoMode(PhotoMode mode)
{
    _photoMode = mode;
    QSettings settings;
    settings.setValue(kPhotoMode, (int)mode);
    emit photoModeChanged();
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoLapse(qreal interval)
{
    _photoLapse = interval;
    QSettings settings;
    settings.setValue(kPhotoLapse, interval);
    emit photoLapseChanged();
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoLapseCount(int count)
{
    _photoLapseCount = count;
    QSettings settings;
    settings.setValue(kPhotoLapseCount, count);
    emit photoLapseCountChanged();
}

Gus Grubba's avatar
Gus Grubba committed
273 274 275 276
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setCameraMode(CameraMode mode)
{
277 278 279 280 281 282 283 284
    _cameraMode = mode;
    emit cameraModeChanged();
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::toggleMode()
{
285
    if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) {
286
        setVideoMode();
287
    } else if(cameraMode() == CAM_MODE_VIDEO) {
288 289 290 291 292
        setPhotoMode();
    }
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
293 294
bool
QGCCameraControl::toggleVideo()
295
{
Gus Grubba's avatar
Gus Grubba committed
296 297 298 299 300 301
    if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
        return stopVideo();
    } else {
        return startVideo();
    }
}
302

Gus Grubba's avatar
Gus Grubba committed
303 304 305 306 307 308
//-----------------------------------------------------------------------------
bool
QGCCameraControl::takePhoto()
{
    qCDebug(CameraControlLog) << "takePhoto()";
    //-- Check if camera can capture photos or if it can capture it while in Video Mode
309
    if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) {
Gus Grubba's avatar
Gus Grubba committed
310 311 312 313
        return false;
    }
    if(capturesPhotos()) {
        _vehicle->sendMavCommand(
314 315 316 317 318 319
            MAV_COMP_ID_CAMERA,                                         // Target component
            MAV_CMD_IMAGE_START_CAPTURE,                                // Command id
            false,                                                      // ShowError
            0,                                                          // Reserved (Set to 0)
            _photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse,       // Duration between two consecutive pictures (in seconds--ignored if single image)
            _photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture
320
        _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS);
321
        _captureInfoRetries = 0;
Gus Grubba's avatar
Gus Grubba committed
322 323 324 325 326 327 328 329
        //-- 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;
330 331
}

332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352
//-----------------------------------------------------------------------------
bool
QGCCameraControl::stopTakePhoto()
{
    qCDebug(CameraControlLog) << "stopTakePhoto()";
    if(photoStatus() == PHOTO_CAPTURE_IDLE || (photoStatus() != PHOTO_CAPTURE_INTERVAL_IDLE && photoStatus() != PHOTO_CAPTURE_INTERVAL_IN_PROGRESS)) {
        return false;
    }
    if(capturesPhotos()) {
        _vehicle->sendMavCommand(
            MAV_COMP_ID_CAMERA,                                         // Target component
            MAV_CMD_IMAGE_STOP_CAPTURE,                                 // Command id
            false,                                                      // ShowError
            0);                                                         // Reserved (Set to 0)
        _setPhotoStatus(PHOTO_CAPTURE_IDLE);
        _captureInfoRetries = 0;
        return true;
    }
    return false;
}

353
//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
354
bool
355 356
QGCCameraControl::startVideo()
{
Gus Grubba's avatar
Gus Grubba committed
357 358
    qCDebug(CameraControlLog) << "startVideo()";
    //-- Check if camera can capture videos or if it can capture it while in Photo Mode
359
    if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) {
Gus Grubba's avatar
Gus Grubba committed
360 361 362 363 364 365 366
        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
367
            0,                                          // Reserved (Set to 0)
Gus Grubba's avatar
Gus Grubba committed
368 369 370 371
            0);                                         // CAMERA_CAPTURE_STATUS Frequency
        return true;
    }
    return false;
372 373 374
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
375
bool
376 377
QGCCameraControl::stopVideo()
{
Gus Grubba's avatar
Gus Grubba committed
378 379 380 381 382 383
    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
384
            0);                                         // Reserved (Set to 0)
Gus Grubba's avatar
Gus Grubba committed
385 386 387
        return true;
    }
    return false;
388 389 390 391 392 393
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setVideoMode()
{
394
    if(hasModes() && _cameraMode != CAM_MODE_VIDEO) {
395 396 397 398 399 400
        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
401
            0,                                      // Reserved (Set to 0)
402 403
            CAM_MODE_VIDEO);                     // Camera mode (0: photo, 1: video)
        _setCameraMode(CAM_MODE_VIDEO);
404 405 406 407 408 409 410
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoMode()
{
411
    if(hasModes() && _cameraMode != CAM_MODE_PHOTO) {
412 413 414 415 416 417
        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
418
            0,                                      // Reserved (Set to 0)
419
            CAM_MODE_PHOTO);                        // Camera mode (0: photo, 1: video)
420
        _setCameraMode(CAM_MODE_PHOTO);
421 422 423 424 425 426 427 428
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::resetSettings()
{
    qCDebug(CameraControlLog) << "resetSettings()";
Gus Grubba's avatar
Gus Grubba committed
429 430 431 432 433
    _vehicle->sendMavCommand(
        _compID,                                // Target component
        MAV_CMD_RESET_CAMERA_SETTINGS,          // Command id
        true,                                   // ShowError
        1);                                     // Do Reset
434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450
}

//-----------------------------------------------------------------------------
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
451 452 453 454
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestCaptureStatus()
{
455
    qCDebug(CameraControlLog) << "_requestCaptureStatus()";
Gus Grubba's avatar
Gus Grubba committed
456 457 458 459 460 461 462
    _vehicle->sendMavCommand(
        _compID,                                // target component
        MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS,  // command id
        false,                                  // showError
        1);                                     // Do Request
}

463 464 465 466 467 468 469 470 471
//-----------------------------------------------------------------------------
void
QGCCameraControl::factChanged(Fact* pFact)
{
    _updateActiveList();
    _updateRanges(pFact);
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
472 473
void
QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle)
474
{
Gus Grubba's avatar
Gus Grubba committed
475 476 477 478
    //-- Is this ours?
    if(_vehicle->id() != vehicleId || compID() != component) {
        return;
    }
479 480 481 482
    if(!noReponseFromVehicle && result == MAV_RESULT_IN_PROGRESS) {
        //-- Do Nothing
        qCDebug(CameraControlLog) << "In progress response for" << command;
    }else if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) {
Gus Grubba's avatar
Gus Grubba committed
483 484 485 486 487
        switch(command) {
            case MAV_CMD_RESET_CAMERA_SETTINGS:
                if(isBasic()) {
                    _requestCameraSettings();
                } else {
488 489
                    QTimer::singleShot(500, this, &QGCCameraControl::_requestAllParameters);
                    QTimer::singleShot(2500, this, &QGCCameraControl::_requestCameraSettings);
Gus Grubba's avatar
Gus Grubba committed
490 491 492 493 494 495 496 497
                }
                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);
498
                _captureStatusTimer.start(1000);
Gus Grubba's avatar
Gus Grubba committed
499
                break;
500 501 502 503 504 505
            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
506
        }
Gus Grubba's avatar
Gus Grubba committed
507
    } else {
508 509 510 511 512 513 514 515 516
        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) {
517
                case MAV_CMD_IMAGE_START_CAPTURE:
518
                case MAV_CMD_IMAGE_STOP_CAPTURE:
519 520 521 522 523 524
                    if(++_captureInfoRetries < 5) {
                        _captureStatusTimer.start(1000);
                    } else {
                        qCDebug(CameraControlLog) << "Giving up requesting capture status";
                    }
                    break;
525 526
                case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
                    if(++_captureInfoRetries < 3) {
527
                        _captureStatusTimer.start(500);
528 529 530 531 532 533
                    } else {
                        qCDebug(CameraControlLog) << "Giving up requesting capture status";
                    }
                    break;
                case MAV_CMD_REQUEST_STORAGE_INFORMATION:
                    if(++_storageInfoRetries < 3) {
534
                        QTimer::singleShot(500, this, &QGCCameraControl::_requestStorageInfo);
535 536 537 538 539
                    } else {
                        qCDebug(CameraControlLog) << "Giving up requesting storage status";
                    }
                    break;
            }
Gus Grubba's avatar
Gus Grubba committed
540
        } else {
541
            qCDebug(CameraControlLog) << "Bad response for" << command << result;
Gus Grubba's avatar
Gus Grubba committed
542
        }
Gus Grubba's avatar
Gus Grubba committed
543 544 545 546 547 548 549 550 551 552
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_setVideoStatus(VideoStatus status)
{
    if(_video_status != status) {
        _video_status = status;
        emit videoStatusChanged();
553
    }
Gus Grubba's avatar
Gus Grubba committed
554 555
}

556 557 558 559 560 561 562 563 564 565
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setPhotoStatus(PhotoStatus status)
{
    if(_photo_status != status) {
        _photo_status = status;
        emit photoStatusChanged();
    }
}

Gus Grubba's avatar
Gus Grubba committed
566 567 568 569
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
{
Gus Grubba's avatar
Gus Grubba committed
570
    QByteArray originalData(bytes);
571 572 573 574 575 576 577 578 579 580 581 582 583 584 585
    //-- 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
586
        qWarning() <<  "Unable to load camera constants from camera definition";
587 588 589 590 591
        return false;
    }
    //-- Load camera parameters
    QDomNodeList paramElements = doc.elementsByTagName(kParameters);
    if(!paramElements.size() || !_loadSettings(paramElements)) {
Gus Grubba's avatar
Gus Grubba committed
592
        qWarning() <<  "Unable to load camera parameters from camera definition";
593 594
        return false;
    }
Gus Grubba's avatar
Gus Grubba committed
595 596
    //-- If this is new, cache it
    if(!_cached) {
597 598
        qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile;
        QFile file(_cacheFile);
Gus Grubba's avatar
Gus Grubba committed
599
        if (!file.open(QIODevice::WriteOnly)) {
600
            qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString());
Gus Grubba's avatar
Gus Grubba committed
601 602 603 604
        } else {
            file.write(originalData);
        }
    }
605 606 607 608 609 610 611 612 613 614 615 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 645 646 647 648 649 650 651 652 653 654 655 656
    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;
        }
657 658 659 660 661 662
        //-- 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);
663 664 665 666 667 668 669
        //-- Is it write only?
        bool writeOnly = false;
        read_attribute(parameterNode, kWriteOnly, writeOnly);
        //-- It can't be both
        if(readOnly && writeOnly) {
            qCritical() << QString("Parameter %1 cannot be both read only and write only").arg(factName);
        }
670
        //-- Param type
671 672 673 674 675 676
        bool unknownType;
        FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
        if (unknownType) {
            qCritical() << QString("Unknown type for parameter %1").arg(factName);
            return false;
        }
677 678 679 680
        //-- By definition, custom types do not have control
        if(factType == FactMetaData::valueTypeCustom) {
            control = false;
        }
681
        //-- Description
682 683 684 685 686
        QString description;
        if(!read_value(parameterNode, kDescription, description)) {
            qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
            return false;
        }
687 688 689 690 691
        //-- Check for updates
        QStringList updates = _loadUpdates(parameterNode);
        if(updates.size()) {
            qCDebug(CameraControlLogVerbose) << "Parameter" << factName << "requires updates for:" << updates;
            _requestUpdates[factName] = updates;
692
        }
693 694
        //-- Build metadata
        FactMetaData* metaData = new FactMetaData(factType, factName, this);
695
        QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
696 697
        metaData->setShortDescription(description);
        metaData->setLongDescription(description);
698 699
        metaData->setHasControl(control);
        metaData->setReadOnly(readOnly);
700
        metaData->setWriteOnly(writeOnly);
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
        //-- 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);
726
                    QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
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 753
                    _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 {
754 755 756 757 758 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 791 792
            {
                //-- Check for Min Value
                QString attr;
                if(read_attribute(parameterNode, kMin, attr)) {
                    QVariant typedValue;
                    QString  errorString;
                    if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
                        metaData->setRawMin(typedValue);
                    } else {
                        qWarning() << "Invalid min value for" << factName
                                   << " type:"  << metaData->type()
                                   << " value:" << attr
                                   << " error:" << errorString;
                    }
                }
            }
            {
                //-- Check for Max Value
                QString attr;
                if(read_attribute(parameterNode, kMax, attr)) {
                    QVariant typedValue;
                    QString  errorString;
                    if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
                        metaData->setRawMax(typedValue);
                    } else {
                        qWarning() << "Invalid max value for" << factName
                                   << " type:"  << metaData->type()
                                   << " value:" << attr
                                   << " error:" << errorString;
                    }
                }
            }
            {
                //-- Check for Step Value
                QString attr;
                if(read_attribute(parameterNode, kStep, attr)) {
                    QVariant typedValue;
                    QString  errorString;
                    if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
793
                        metaData->setRawIncrement(typedValue.toDouble());
794 795 796 797 798 799 800 801 802 803 804 805 806 807 808
                    } else {
                        qWarning() << "Invalid step value for" << factName
                                   << " type:"  << metaData->type()
                                   << " value:" << attr
                                   << " error:" << errorString;
                    }
                }
            }
            {
                //-- Check for Units
                QString attr;
                if(read_attribute(parameterNode, kUnit, attr)) {
                    metaData->setRawUnits(attr);
                }
            }
809
            qCDebug(CameraControlLog) << "New parameter:" << factName << (readOnly ? "ReadOnly" : "Writable") << (writeOnly ? "WriteOnly" : "Readable");
810 811
            _nameToFactMetaDataMap[factName] = metaData;
            Fact* pFact = new Fact(_compID, factName, factType, this);
812
            QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
813
            pFact->setMetaData(metaData);
Gus Grubba's avatar
Gus Grubba committed
814
            pFact->_containerSetRawValue(metaData->rawDefaultValue());
815
            QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle);
816
            QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership);
817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 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
            _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
920 921 922 923 924 925
    foreach(QString paramName, _paramIO.keys()) {
        if(_paramIO[paramName]) {
            _paramIO[paramName]->setParamRequest();
        } else {
            qCritical() << "QGCParamIO is NULL" << paramName;
        }
926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957
    }
    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;
    }
958 959 960 961 962
    if(_paramIO[paramName]) {
        _paramIO[paramName]->handleParamAck(ack);
    } else {
        qCritical() << "QGCParamIO is NULL" << paramName;
    }
963 964 965 966 967 968 969 970 971 972 973
}

//-----------------------------------------------------------------------------
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;
    }
974 975 976 977 978
    if(_paramIO[paramName]) {
        _paramIO[paramName]->handleParamValue(value);
    } else {
        qCritical() << "QGCParamIO is NULL" << paramName;
    }
979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995
}

//-----------------------------------------------------------------------------
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;
            }
        }
    }
996
    QStringList active;
997 998
    foreach(QString key, _settings) {
        if(!exclusionList.contains(key)) {
999
            active.append(key);
1000 1001
        }
    }
1002 1003 1004 1005 1006
    if(active != _activeSettings) {
        qCDebug(CameraControlLogVerbose) << "Excluding" << exclusionList;
        _activeSettings = active;
        emit activeSettingsChanged();
    }
1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090
}

//-----------------------------------------------------------------------------
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)
{
1091 1092
    QMap<Fact*, QGCCameraOptionRange*> rangesSet;
    QMap<Fact*, QString> rangesReset;
1093 1094
    QStringList changedList;
    QStringList resetList;
1095
    QStringList updates;
1096
    //-- Iterate range sets looking for limited ranges
1097 1098 1099 1100 1101 1102
    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) {
1103
                //qCDebug(CameraControlLogVerbose) << "Check new set of options for" << pTFact->name();
1104 1105
                QString option = pRFact->rawValueString();  //-- This parameter value
                //-- If this value (and condition) triggers a change in the target range
1106
                //qCDebug(CameraControlLogVerbose) << "Range value:" << pRange->value << "Current value:" << option << "Condition:" << pRange->condition;
1107
                if(pRange->value == option && _processCondition(pRange->condition)) {
1108
                    if(pTFact->enumStrings() != pRange->optNames) {
1109 1110
                        //-- Set limited range set
                        rangesSet[pTFact] = pRange;
1111
                    }
1112
                    changedList << pRange->targetParam;
1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124
                }
            }
        }
    }
    //-- 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;
1125
                }
1126
                resetList << pRange->targetParam;
1127 1128 1129
            }
        }
    }
1130
    //-- Update limited range set
1131 1132 1133 1134 1135 1136 1137 1138
    foreach (Fact* f, rangesSet.keys()) {
        f->setEnumInfo(rangesSet[f]->optNames, rangesSet[f]->optVariants);
        if(!updates.contains(f->name())) {
            _paramIO[f->name()]->optNames = rangesSet[f]->optNames;
            _paramIO[f->name()]->optVariants = rangesSet[f]->optVariants;
            emit f->enumsChanged();
            qCDebug(CameraControlLogVerbose) << "Limited set of options for:" << f->name() << rangesSet[f]->optNames;;
            updates << f->name();
1139 1140 1141
        }
    }
    //-- Restore full range set
1142 1143 1144 1145 1146 1147 1148 1149
    foreach (Fact* f, rangesReset.keys()) {
        f->setEnumInfo(_originalOptNames[rangesReset[f]], _originalOptValues[rangesReset[f]]);
        if(!updates.contains(f->name())) {
            _paramIO[f->name()]->optNames = _originalOptNames[rangesReset[f]];
            _paramIO[f->name()]->optVariants = _originalOptValues[rangesReset[f]];
            emit f->enumsChanged();
            qCDebug(CameraControlLogVerbose) << "Restore full set of options for:" << f->name() << _originalOptNames[f->name()];
            updates << f->name();
1150 1151
        }
    }
1152 1153
    //-- Parameter update requests
    if(_requestUpdates.contains(pFact->name())) {
1154
        foreach(QString param, _requestUpdates[pFact->name()]) {
1155 1156 1157
            if(!_updatesToRequest.contains(param)) {
                _updatesToRequest << param;
            }
1158
        }
1159
    }
1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172
    if(_updatesToRequest.size()) {
        QTimer::singleShot(500, this, &QGCCameraControl::_requestParamUpdates);
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestParamUpdates()
{
    foreach(QString param, _updatesToRequest) {
        _paramIO[param]->paramRequest();
    }
    _updatesToRequest.clear();
1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188
}

//-----------------------------------------------------------------------------
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
1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203
//-----------------------------------------------------------------------------
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
    }
}

1204 1205 1206 1207
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
{
Gus Grubba's avatar
Gus Grubba committed
1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238
    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();
    }
1239
    //-- Video/Image Capture Status
1240 1241 1242 1243
    uint8_t vs = cap.video_status < (uint8_t)VIDEO_CAPTURE_STATUS_LAST ? cap.video_status : (uint8_t)VIDEO_CAPTURE_STATUS_UNDEFINED;
    uint8_t ps = cap.image_status < (uint8_t)PHOTO_CAPTURE_LAST ? cap.image_status : (uint8_t)PHOTO_CAPTURE_STATUS_UNDEFINED;
    _setVideoStatus((VideoStatus)vs);
    _setPhotoStatus((PhotoStatus)ps);
Gus Grubba's avatar
Gus Grubba committed
1244 1245 1246
    //-- Keep asking for it once in a while when recording
    if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
        _captureStatusTimer.start(5000);
1247 1248
    //-- Same while (single) image capture is busy
    } else if(photoStatus() != PHOTO_CAPTURE_IDLE && photoMode() == PHOTO_CAPTURE_SINGLE) {
1249
        _captureStatusTimer.start(1000);
Gus Grubba's avatar
Gus Grubba committed
1250
    }
1251 1252 1253 1254 1255 1256 1257 1258
    //-- Time Lapse
    if(photoStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) {
        //-- 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);
    }
1259 1260 1261 1262 1263 1264 1265 1266 1267 1268
}

//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadExclusions(QDomNode option)
{
    QStringList exclusionList;
    QDomElement optionElem = option.toElement();
    QDomNodeList excRoot = optionElem.elementsByTagName(kExclusions);
    if(excRoot.size()) {
1269
        //-- Iterate exclusions
1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282
        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;
}

1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304
//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadUpdates(QDomNode option)
{
    QStringList updateList;
    QDomElement optionElem = option.toElement();
    QDomNodeList updateRoot = optionElem.elementsByTagName(kUpdates);
    if(updateRoot.size()) {
        //-- Iterate updates
        QDomNode node = updateRoot.item(0);
        QDomElement elem = node.toElement();
        QDomNodeList updates = elem.elementsByTagName(kUpdate);
        for(int i = 0; i < updates.size(); i++) {
            QString update = updates.item(i).toElement().text();
            if(!update.isEmpty()) {
                updateList << update;
            }
        }
    }
    return updateList;
}

1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400
//-----------------------------------------------------------------------------
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
1401

Gus Grubba's avatar
Gus Grubba committed
1402 1403 1404 1405 1406
//-----------------------------------------------------------------------------
void
QGCCameraControl::_handleDefinitionFile(const QString &url)
{
    //-- First check and see if we have it cached
1407
    QFile xmlFile(_cacheFile);
Gus Grubba's avatar
Gus Grubba committed
1408 1409 1410 1411 1412 1413
    if (!xmlFile.exists()) {
        qCDebug(CameraControlLog) << "No camera definition file cached";
        _httpRequest(url);
        return;
    }
    if (!xmlFile.open(QIODevice::ReadOnly)) {
1414
        qWarning() << "Could not read cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1415 1416 1417 1418 1419 1420
        _httpRequest(url);
        return;
    }
    QByteArray bytes = xmlFile.readAll();
    QDomDocument doc;
    if(!doc.setContent(bytes, false)) {
1421
        qWarning() << "Could not parse cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1422 1423 1424 1425
        _httpRequest(url);
        return;
    }
    //-- We have it
1426
    qCDebug(CameraControlLog) << "Using cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1427 1428 1429 1430
    _cached = true;
    emit dataReady(bytes);
}

Gus Grubba's avatar
Gus Grubba committed
1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480
//-----------------------------------------------------------------------------
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);
1481 1482
    } else {
        qCDebug(CameraControlLog) << "No camera definition";
Gus Grubba's avatar
Gus Grubba committed
1483 1484 1485
    }
    _initWhenReady();
}
1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496

//-----------------------------------------------------------------------------
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
1497
    emit parametersReady();
1498
}
1499 1500 1501 1502 1503 1504 1505 1506 1507

//-----------------------------------------------------------------------------
bool
QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue)
{
    Q_UNUSED(pFact);
    Q_UNUSED(newValue);
    return true;
}
1508 1509 1510 1511 1512 1513 1514 1515 1516

//-----------------------------------------------------------------------------
bool
QGCCameraControl::validateParameter(Fact* pFact, QVariant& newValue)
{
    Q_UNUSED(pFact);
    Q_UNUSED(newValue);
    return true;
}
Gus Grubba's avatar
Gus Grubba committed
1517 1518 1519 1520 1521 1522 1523 1524

//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::activeSettings()
{
    qCDebug(CameraControlLog) << "Active:" << _activeSettings;
    return _activeSettings;
}