QGCCameraControl.cc 80.3 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
#include "SettingsManager.h"
#include "VideoManager.h"
#include "QGCMapEngine.h"
13
#include "QGCCameraManager.h"
Gus Grubba's avatar
Gus Grubba committed
14

Gus Grubba's avatar
Gus Grubba committed
15
#include <QDir>
Gus Grubba's avatar
Gus Grubba committed
16
#include <QStandardPaths>
17 18 19 20
#include <QDomDocument>
#include <QDomNodeList>

QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog")
21
QGC_LOGGING_CATEGORY(CameraControlVerboseLog, "CameraControlVerboseLog")
22

23
static const char* kCondition       = "condition";
24 25
static const char* kControl         = "control";
static const char* kDefault         = "default";
26
static const char* kDefnition       = "definition";
27 28
static const char* kDescription     = "description";
static const char* kExclusion       = "exclude";
29 30 31
static const char* kExclusions      = "exclusions";
static const char* kLocale          = "locale";
static const char* kLocalization    = "localization";
32 33
static const char* kMax             = "max";
static const char* kMin             = "min";
34 35 36 37
static const char* kModel           = "model";
static const char* kName            = "name";
static const char* kOption          = "option";
static const char* kOptions         = "options";
38
static const char* kOriginal        = "original";
39 40 41 42 43
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";
44
static const char* kWriteOnly       = "writeonly";
45
static const char* kRoption         = "roption";
46
static const char* kStep            = "step";
47
static const char* kDecimalPlaces   = "decimalPlaces";
48
static const char* kStrings         = "strings";
49
static const char* kTranslated      = "translated";
50
static const char* kType            = "type";
51
static const char* kUnit            = "unit";
52 53 54 55 56
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";
57

58 59 60
static const char* kPhotoMode       = "PhotoMode";
static const char* kPhotoLapse      = "PhotoLapse";
static const char* kPhotoLapseCount = "PhotoLapseCount";
61 62
static const char* kThermalOpacity  = "ThermalOpacity";
static const char* kThermalMode     = "ThermalMode";
63

64 65
//-----------------------------------------------------------------------------
// Known Parameters
66 67 68 69 70 71 72
const char* QGCCameraControl::kCAM_EV          = "CAM_EV";
const char* QGCCameraControl::kCAM_EXPMODE     = "CAM_EXPMODE";
const char* QGCCameraControl::kCAM_ISO         = "CAM_ISO";
const char* QGCCameraControl::kCAM_SHUTTERSPD  = "CAM_SHUTTERSPD";
const char* QGCCameraControl::kCAM_APERTURE    = "CAM_APERTURE";
const char* QGCCameraControl::kCAM_WBMODE      = "CAM_WBMODE";
const char* QGCCameraControl::kCAM_MODE        = "CAM_MODE";
73

Gus Grubba's avatar
Gus Grubba committed
74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94
//-----------------------------------------------------------------------------
QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
    : QObject(parent)
    , param(param_)
    , value(value_)
    , exclusions(exclusions_)
{
}

//-----------------------------------------------------------------------------
QGCCameraOptionRange::QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
    : QObject(parent)
    , param(param_)
    , value(value_)
    , targetParam(targetParam_)
    , condition(condition_)
    , optNames(optNames_)
    , optValues(optValues_)
{
}

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 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160
//-----------------------------------------------------------------------------
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)
{
161
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
162
    memcpy(&_info, info, sizeof(mavlink_camera_information_t));
Gus Grubba's avatar
Gus Grubba committed
163
    connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
Gus Grubba's avatar
Gus Grubba committed
164 165 166
    _vendor = QString(reinterpret_cast<const char*>(info->vendor_name));
    _modelName = QString(reinterpret_cast<const char*>(info->model_name));
    int ver = static_cast<int>(_info.cam_definition_version);
167 168 169 170 171
    _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
172
    if(info->cam_definition_uri[0] != 0) {
Gus Grubba's avatar
Gus Grubba committed
173
        //-- Process camera definition file
Gus Grubba's avatar
Gus Grubba committed
174
        _handleDefinitionFile(info->cam_definition_uri);
Gus Grubba's avatar
Gus Grubba committed
175 176 177
    } else {
        _initWhenReady();
    }
178
    QSettings settings;
179 180
    _photoMode       = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
    _photoLapse      = settings.value(kPhotoLapse, 1.0).toDouble();
181
    _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
182 183
    _thermalOpacity  = settings.value(kThermalOpacity, 85.0).toDouble();
    _thermalMode     = static_cast<ThermalViewMode>(settings.value(kThermalMode, static_cast<uint32_t>(THERMAL_BLEND)).toUInt());
184 185 186
    _recTimer.setSingleShot(false);
    _recTimer.setInterval(333);
    connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler);
187 188 189 190 191
}

//-----------------------------------------------------------------------------
QGCCameraControl::~QGCCameraControl()
{
Gus Grubba's avatar
Gus Grubba committed
192 193 194 195 196 197 198 199 200 201 202 203 204
    if(_netManager) {
        delete _netManager;
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_initWhenReady()
{
    qCDebug(CameraControlLog) << "_initWhenReady()";
    if(isBasic()) {
        qCDebug(CameraControlLog) << "Basic, MAVLink only messages.";
        _requestCameraSettings();
205
        QTimer::singleShot(250, this, &QGCCameraControl::_checkForVideoStreams);
206 207 208
        //-- Basic cameras have no parameters
        _paramComplete = true;
        emit parametersReady();
Gus Grubba's avatar
Gus Grubba committed
209 210 211 212 213 214 215 216 217 218 219 220 221
    } 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;
Gus Grubba's avatar
Gus Grubba committed
222
        _netManager = nullptr;
Gus Grubba's avatar
Gus Grubba committed
223
    }
224 225 226 227 228 229 230 231 232 233 234 235 236 237
}

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

238 239 240 241 242 243 244
//-----------------------------------------------------------------------------
QString
QGCCameraControl::recordTimeStr()
{
    return QTime(0, 0).addMSecs(static_cast<int>(recordTime())).toString("hh:mm:ss");
}

Gus Grubba's avatar
Gus Grubba committed
245 246 247 248 249 250 251
//-----------------------------------------------------------------------------
QGCCameraControl::VideoStatus
QGCCameraControl::videoStatus()
{
    return _video_status;
}

252 253 254 255 256 257 258
//-----------------------------------------------------------------------------
QGCCameraControl::PhotoStatus
QGCCameraControl::photoStatus()
{
    return _photo_status;
}

Gus Grubba's avatar
Gus Grubba committed
259 260 261 262
//-----------------------------------------------------------------------------
QString
QGCCameraControl::storageFreeStr()
{
263
    return QGCMapEngine::storageFreeSizeToString(static_cast<quint64>(_storageFree));
Gus Grubba's avatar
Gus Grubba committed
264 265
}

266 267 268 269
//-----------------------------------------------------------------------------
void
QGCCameraControl::setCameraMode(CameraMode mode)
{
270 271 272 273 274 275 276 277
    if(!_resetting) {
        qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")";
        if(mode == CAM_MODE_VIDEO) {
            setVideoMode();
        } else if(mode == CAM_MODE_PHOTO) {
            setPhotoMode();
        } else {
            qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode;
278
        }
279
    }
Gus Grubba's avatar
Gus Grubba committed
280 281
}

282 283 284 285
//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoMode(PhotoMode mode)
{
286 287 288 289 290 291
    if(!_resetting) {
        _photoMode = mode;
        QSettings settings;
        settings.setValue(kPhotoMode, static_cast<int>(mode));
        emit photoModeChanged();
    }
292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313
}

//-----------------------------------------------------------------------------
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
314 315 316 317
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setCameraMode(CameraMode mode)
{
318 319 320 321 322 323
    if(_cameraMode != mode) {
        _cameraMode = mode;
        emit cameraModeChanged();
        //-- Update stream status
        _streamStatusTimer.start(1000);
    }
324 325 326 327 328 329
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::toggleMode()
{
330 331 332 333 334 335
    if(!_resetting) {
        if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) {
            setVideoMode();
        } else if(cameraMode() == CAM_MODE_VIDEO) {
            setPhotoMode();
        }
336 337 338 339
    }
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
340 341
bool
QGCCameraControl::toggleVideo()
342
{
343 344 345 346 347 348
    if(!_resetting) {
        if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
            return stopVideo();
        } else {
            return startVideo();
        }
Gus Grubba's avatar
Gus Grubba committed
349
    }
350
    return false;
Gus Grubba's avatar
Gus Grubba committed
351
}
352

Gus Grubba's avatar
Gus Grubba committed
353 354 355 356 357 358
//-----------------------------------------------------------------------------
bool
QGCCameraControl::takePhoto()
{
    qCDebug(CameraControlLog) << "takePhoto()";
    //-- Check if camera can capture photos or if it can capture it while in Video Mode
359 360 361 362 363 364 365 366 367 368
    if(!capturesPhotos()) {
        qCWarning(CameraControlLog) << "Camera does not handle image capture";
        return false;
    }
    if(cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) {
        qCWarning(CameraControlLog) << "Camera does not handle image capture while in video mode";
        return false;
    }
    if(photoStatus() != PHOTO_CAPTURE_IDLE) {
        qCWarning(CameraControlLog) << "Camera not idle";
Gus Grubba's avatar
Gus Grubba committed
369 370
        return false;
    }
371 372 373 374 375 376 377 378 379 380 381 382
    if(!_resetting) {
        if(capturesPhotos()) {
            _vehicle->sendMavCommand(
                _compID,                                                                    // Target component
                MAV_CMD_IMAGE_START_CAPTURE,                                                // Command id
                false,                                                                      // ShowError
                0,                                                                          // Reserved (Set to 0)
                static_cast<float>(_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
            _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS);
            _captureInfoRetries = 0;
            //-- Capture local image as well
383 384 385 386 387 388
            if(qgcApp()->toolbox()->videoManager()->videoReceiver()) {
                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);
            }
389 390
            return true;
        }
Gus Grubba's avatar
Gus Grubba committed
391 392
    }
    return false;
393 394
}

395 396 397 398
//-----------------------------------------------------------------------------
bool
QGCCameraControl::stopTakePhoto()
{
399 400 401 402 403 404 405 406 407 408 409 410 411 412 413
    if(!_resetting) {
        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(
                _compID,                                                    // Target component
                MAV_CMD_IMAGE_STOP_CAPTURE,                                 // Command id
                false,                                                      // ShowError
                0);                                                         // Reserved (Set to 0)
            _setPhotoStatus(PHOTO_CAPTURE_IDLE);
            _captureInfoRetries = 0;
            return true;
        }
414 415 416 417
    }
    return false;
}

418
//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
419
bool
420 421
QGCCameraControl::startVideo()
{
422 423 424 425 426 427 428 429 430 431
    if(!_resetting) {
        qCDebug(CameraControlLog) << "startVideo()";
        //-- Check if camera can capture videos or if it can capture it while in Photo Mode
        if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) {
            return false;
        }
        if(videoStatus() != VIDEO_CAPTURE_STATUS_RUNNING) {
            _vehicle->sendMavCommand(
                _compID,                                    // Target component
                MAV_CMD_VIDEO_START_CAPTURE,                // Command id
432
                false,                                      // Don't Show Error (handle locally)
433 434 435 436
                0,                                          // Reserved (Set to 0)
                0);                                         // CAMERA_CAPTURE_STATUS Frequency
            return true;
        }
Gus Grubba's avatar
Gus Grubba committed
437 438
    }
    return false;
439 440 441
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
442
bool
443 444
QGCCameraControl::stopVideo()
{
445 446 447 448 449 450
    if(!_resetting) {
        qCDebug(CameraControlLog) << "stopVideo()";
        if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
            _vehicle->sendMavCommand(
                _compID,                                    // Target component
                MAV_CMD_VIDEO_STOP_CAPTURE,                 // Command id
451
                false,                                      // Don't Show Error (handle locally)
452 453 454
                0);                                         // Reserved (Set to 0)
            return true;
        }
Gus Grubba's avatar
Gus Grubba committed
455 456
    }
    return false;
457 458 459 460 461 462
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setVideoMode()
{
463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483
    if(!_resetting && hasModes()) {
        qCDebug(CameraControlLog) << "setVideoMode()";
        //-- Does it have a mode parameter?
        Fact* pMode = mode();
        if(pMode) {
            if(cameraMode() != CAM_MODE_VIDEO) {
                pMode->setRawValue(CAM_MODE_VIDEO);
                _setCameraMode(CAM_MODE_VIDEO);
            }
        } else {
            //-- Use MAVLink Command
            if(_cameraMode != CAM_MODE_VIDEO) {
                //-- Use basic MAVLink message
                _vehicle->sendMavCommand(
                    _compID,                                // Target component
                    MAV_CMD_SET_CAMERA_MODE,                // Command id
                    true,                                   // ShowError
                    0,                                      // Reserved (Set to 0)
                    CAM_MODE_VIDEO);                        // Camera mode (0: photo, 1: video)
                _setCameraMode(CAM_MODE_VIDEO);
            }
484
        }
485 486 487 488 489 490 491
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoMode()
{
492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512
    if(!_resetting && hasModes()) {
        qCDebug(CameraControlLog) << "setPhotoMode()";
        //-- Does it have a mode parameter?
        Fact* pMode = mode();
        if(pMode) {
            if(cameraMode() != CAM_MODE_PHOTO) {
                pMode->setRawValue(CAM_MODE_PHOTO);
                _setCameraMode(CAM_MODE_PHOTO);
            }
        } else {
            //-- Use MAVLink Command
            if(_cameraMode != CAM_MODE_PHOTO) {
                //-- Use basic MAVLink message
                _vehicle->sendMavCommand(
                    _compID,                                // Target component
                    MAV_CMD_SET_CAMERA_MODE,                // Command id
                    true,                                   // ShowError
                    0,                                      // Reserved (Set to 0)
                    CAM_MODE_PHOTO);                        // Camera mode (0: photo, 1: video)
                _setCameraMode(CAM_MODE_PHOTO);
            }
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
//-----------------------------------------------------------------------------
void
QGCCameraControl::setThermalMode(ThermalViewMode mode)
{
    QSettings settings;
    settings.setValue(kThermalMode, static_cast<uint32_t>(mode));
    _thermalMode = mode;
    emit thermalModeChanged();
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setThermalOpacity(double val)
{
    if(val < 0.0) val = 0.0;
    if(val > 100.0) val = 100.0;
    if(fabs(_thermalOpacity - val) > 0.1) {
        _thermalOpacity = val;
        QSettings settings;
        settings.setValue(kThermalOpacity, val);
        emit thermalOpacityChanged();
    }
}

541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578
//-----------------------------------------------------------------------------
void
QGCCameraControl::setZoomLevel(qreal level)
{
    qCDebug(CameraControlLog) << "setZoomLevel()" << level;
    if(hasZoom()) {
        //-- Limit
        level = std::min(std::max(level, 0.0), 100.0);
        if(_vehicle) {
            _vehicle->sendMavCommand(
                _compID,                                // Target component
                MAV_CMD_SET_CAMERA_ZOOM,                // Command id
                false,                                  // ShowError
                ZOOM_TYPE_RANGE,                        // Zoom type
                static_cast<float>(level));             // Level
        }
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setFocusLevel(qreal level)
{
    qCDebug(CameraControlLog) << "setFocusLevel()" << level;
    if(hasFocus()) {
        //-- Limit
        level = std::min(std::max(level, 0.0), 100.0);
        if(_vehicle) {
            _vehicle->sendMavCommand(
                _compID,                                // Target component
                MAV_CMD_SET_CAMERA_FOCUS,               // Command id
                false,                                  // ShowError
                FOCUS_TYPE_RANGE,                       // Focus type
                static_cast<float>(level));             // Level
        }
    }
}

579 580 581 582
//-----------------------------------------------------------------------------
void
QGCCameraControl::resetSettings()
{
583 584 585 586 587 588 589 590 591
    if(!_resetting) {
        qCDebug(CameraControlLog) << "resetSettings()";
        _resetting = true;
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_RESET_CAMERA_SETTINGS,          // Command id
            true,                                   // ShowError
            1);                                     // Do Reset
    }
592 593 594 595 596 597
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::formatCard(int id)
{
598 599 600 601 602 603 604 605 606 607
    if(!_resetting) {
        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
        }
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
//-----------------------------------------------------------------------------
void
QGCCameraControl::stepZoom(int direction)
{
    qCDebug(CameraControlLog) << "stepZoom()" << direction;
    if(_vehicle && hasZoom()) {
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_SET_CAMERA_ZOOM,                // Command id
            false,                                  // ShowError
            ZOOM_TYPE_STEP,                         // Zoom type
            direction);                             // Direction (-1 wide, 1 tele)
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::startZoom(int direction)
{
    qCDebug(CameraControlLog) << "startZoom()" << direction;
    if(_vehicle && hasZoom()) {
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_SET_CAMERA_ZOOM,                // Command id
635
            false,                                  // ShowError
636 637 638 639 640 641 642 643 644 645 646 647 648 649
            ZOOM_TYPE_CONTINUOUS,                   // Zoom type
            direction);                             // Direction (-1 wide, 1 tele)
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::stopZoom()
{
    qCDebug(CameraControlLog) << "stopZoom()";
    if(_vehicle && hasZoom()) {
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_SET_CAMERA_ZOOM,                // Command id
650
            false,                                  // ShowError
651 652 653 654 655
            ZOOM_TYPE_CONTINUOUS,                   // Zoom type
            0);                                     // Direction (-1 wide, 1 tele)
    }
}

Gus Grubba's avatar
Gus Grubba committed
656 657 658 659
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestCaptureStatus()
{
660
    qCDebug(CameraControlLog) << "_requestCaptureStatus()";
Gus Grubba's avatar
Gus Grubba committed
661 662 663 664 665 666 667
    _vehicle->sendMavCommand(
        _compID,                                // target component
        MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS,  // command id
        false,                                  // showError
        1);                                     // Do Request
}

668 669 670 671 672 673 674 675 676
//-----------------------------------------------------------------------------
void
QGCCameraControl::factChanged(Fact* pFact)
{
    _updateActiveList();
    _updateRanges(pFact);
}

//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
677 678
void
QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle)
679
{
Gus Grubba's avatar
Gus Grubba committed
680 681 682 683
    //-- Is this ours?
    if(_vehicle->id() != vehicleId || compID() != component) {
        return;
    }
684 685 686 687
    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
688 689
        switch(command) {
            case MAV_CMD_RESET_CAMERA_SETTINGS:
690
                _resetting = false;
Gus Grubba's avatar
Gus Grubba committed
691 692 693
                if(isBasic()) {
                    _requestCameraSettings();
                } else {
694 695
                    QTimer::singleShot(500, this, &QGCCameraControl::_requestAllParameters);
                    QTimer::singleShot(2500, this, &QGCCameraControl::_requestCameraSettings);
Gus Grubba's avatar
Gus Grubba committed
696 697 698 699 700 701 702 703
                }
                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);
704
                _captureStatusTimer.start(1000);
Gus Grubba's avatar
Gus Grubba committed
705
                break;
706 707 708 709 710 711
            case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
                _captureInfoRetries = 0;
                break;
            case MAV_CMD_REQUEST_STORAGE_INFORMATION:
                _storageInfoRetries = 0;
                break;
712 713 714
            case MAV_CMD_IMAGE_START_CAPTURE:
                _captureStatusTimer.start(1000);
                break;
Gus Grubba's avatar
Gus Grubba committed
715
        }
Gus Grubba's avatar
Gus Grubba committed
716
    } else {
717 718 719 720 721 722 723 724 725
        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) {
726
                case MAV_CMD_IMAGE_START_CAPTURE:
727
                case MAV_CMD_IMAGE_STOP_CAPTURE:
728
                    if(++_captureInfoRetries < 3) {
729 730
                        _captureStatusTimer.start(1000);
                    } else {
731 732
                        qCDebug(CameraControlLog) << "Giving up start/stop image capture";
                        _setPhotoStatus(PHOTO_CAPTURE_IDLE);
733 734
                    }
                    break;
735 736
                case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
                    if(++_captureInfoRetries < 3) {
737
                        _captureStatusTimer.start(500);
738 739 740 741 742 743
                    } else {
                        qCDebug(CameraControlLog) << "Giving up requesting capture status";
                    }
                    break;
                case MAV_CMD_REQUEST_STORAGE_INFORMATION:
                    if(++_storageInfoRetries < 3) {
744
                        QTimer::singleShot(500, this, &QGCCameraControl::_requestStorageInfo);
745 746 747 748 749
                    } else {
                        qCDebug(CameraControlLog) << "Giving up requesting storage status";
                    }
                    break;
            }
Gus Grubba's avatar
Gus Grubba committed
750
        } else {
751
            qCDebug(CameraControlLog) << "Bad response for" << command << result;
Gus Grubba's avatar
Gus Grubba committed
752
        }
Gus Grubba's avatar
Gus Grubba committed
753 754 755 756 757 758 759 760 761 762
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_setVideoStatus(VideoStatus status)
{
    if(_video_status != status) {
        _video_status = status;
        emit videoStatusChanged();
763 764 765 766 767 768 769 770 771
        if(status == VIDEO_CAPTURE_STATUS_RUNNING) {
             _recordTime = 0;
             _recTime.start();
             _recTimer.start();
        } else {
             _recTimer.stop();
             _recordTime = 0;
             emit recordTimeChanged();
        }
772
    }
Gus Grubba's avatar
Gus Grubba committed
773 774
}

775 776 777 778 779 780 781 782
//-----------------------------------------------------------------------------
void
QGCCameraControl::_recTimerHandler()
{
    _recordTime = static_cast<uint32_t>(_recTime.elapsed());
    emit recordTimeChanged();
}

783 784 785 786 787
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setPhotoStatus(PhotoStatus status)
{
    if(_photo_status != status) {
788
        qCDebug(CameraControlLog) << "Set Photo Status:" << status;
789 790 791 792 793
        _photo_status = status;
        emit photoStatusChanged();
    }
}

Gus Grubba's avatar
Gus Grubba committed
794 795 796 797
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
{
Gus Grubba's avatar
Gus Grubba committed
798
    QByteArray originalData(bytes);
799 800 801 802 803 804 805 806 807 808 809 810 811 812 813
    //-- 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
814
        qWarning() <<  "Unable to load camera constants from camera definition";
815 816 817 818 819
        return false;
    }
    //-- Load camera parameters
    QDomNodeList paramElements = doc.elementsByTagName(kParameters);
    if(!paramElements.size() || !_loadSettings(paramElements)) {
Gus Grubba's avatar
Gus Grubba committed
820
        qWarning() <<  "Unable to load camera parameters from camera definition";
821 822
        return false;
    }
Gus Grubba's avatar
Gus Grubba committed
823 824
    //-- If this is new, cache it
    if(!_cached) {
825 826
        qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile;
        QFile file(_cacheFile);
Gus Grubba's avatar
Gus Grubba committed
827
        if (!file.open(QIODevice::WriteOnly)) {
828
            qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString());
Gus Grubba's avatar
Gus Grubba committed
829 830 831 832
        } else {
            file.write(originalData);
        }
    }
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
    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;
        }
885 886 887 888 889 890
        //-- 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);
891 892 893 894 895 896 897
        //-- 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);
        }
898
        //-- Param type
899 900 901 902 903 904
        bool unknownType;
        FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
        if (unknownType) {
            qCritical() << QString("Unknown type for parameter %1").arg(factName);
            return false;
        }
905 906 907 908
        //-- By definition, custom types do not have control
        if(factType == FactMetaData::valueTypeCustom) {
            control = false;
        }
909
        //-- Description
910 911 912 913 914
        QString description;
        if(!read_value(parameterNode, kDescription, description)) {
            qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
            return false;
        }
915 916 917
        //-- Check for updates
        QStringList updates = _loadUpdates(parameterNode);
        if(updates.size()) {
918
            qCDebug(CameraControlVerboseLog) << "Parameter" << factName << "requires updates for:" << updates;
919
            _requestUpdates[factName] = updates;
920
        }
921 922
        //-- Build metadata
        FactMetaData* metaData = new FactMetaData(factType, factName, this);
923
        QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
924 925
        metaData->setShortDescription(description);
        metaData->setLongDescription(description);
926 927
        metaData->setHasControl(control);
        metaData->setReadOnly(readOnly);
928
        metaData->setWriteOnly(writeOnly);
929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951
        //-- 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()) {
952
                    qCDebug(CameraControlVerboseLog) << "New exclusions:" << factName << optValue << exclusions;
953
                    QGCCameraOptionExclusion* pExc = new QGCCameraOptionExclusion(this, factName, optValue, exclusions);
954
                    QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981
                    _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 {
982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020
            {
                //-- 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)) {
1021
                        metaData->setRawIncrement(typedValue.toDouble());
1022 1023 1024 1025 1026 1027 1028 1029
                    } else {
                        qWarning() << "Invalid step value for" << factName
                                   << " type:"  << metaData->type()
                                   << " value:" << attr
                                   << " error:" << errorString;
                    }
                }
            }
1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045
            {
                //-- Check for Decimal Places
                QString attr;
                if(read_attribute(parameterNode, kDecimalPlaces, attr)) {
                    QVariant typedValue;
                    QString  errorString;
                    if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
                        metaData->setDecimalPlaces(typedValue.toInt());
                    } else {
                        qWarning() << "Invalid decimal places value for" << factName
                                   << " type:"  << metaData->type()
                                   << " value:" << attr
                                   << " error:" << errorString;
                    }
                }
            }
1046 1047 1048 1049 1050 1051 1052
            {
                //-- Check for Units
                QString attr;
                if(read_attribute(parameterNode, kUnit, attr)) {
                    metaData->setRawUnits(attr);
                }
            }
1053
            qCDebug(CameraControlLog) << "New parameter:" << factName << (readOnly ? "ReadOnly" : "Writable") << (writeOnly ? "WriteOnly" : "Readable");
1054 1055
            _nameToFactMetaDataMap[factName] = metaData;
            Fact* pFact = new Fact(_compID, factName, factType, this);
1056
            QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
1057
            pFact->setMetaData(metaData);
Gus Grubba's avatar
Gus Grubba committed
1058
            pFact->_containerSetRawValue(metaData->rawDefaultValue());
1059
            QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle);
1060
            QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership);
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
            _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();
1089
#if defined (Q_OS_MAC)
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
    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
1164
    for(const QString& paramName: _paramIO.keys()) {
1165 1166 1167 1168 1169
        if(_paramIO[paramName]) {
            _paramIO[paramName]->setParamRequest();
        } else {
            qCritical() << "QGCParamIO is NULL" << paramName;
        }
1170 1171 1172 1173
    }
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    mavlink_message_t msg;
    mavlink_msg_param_ext_request_list_pack_chan(
Gus Grubba's avatar
Gus Grubba committed
1174 1175
        static_cast<uint8_t>(mavlink->getSystemId()),
        static_cast<uint8_t>(mavlink->getComponentId()),
1176 1177
        _vehicle->priorityLink()->mavlinkChannel(),
        &msg,
Gus Grubba's avatar
Gus Grubba committed
1178 1179
        static_cast<uint8_t>(_vehicle->id()),
        static_cast<uint8_t>(compID()));
1180
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
1181
    qCDebug(CameraControlVerboseLog) << "Request all parameters";
1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201
}

//-----------------------------------------------------------------------------
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;
    }
1202 1203 1204 1205 1206
    if(_paramIO[paramName]) {
        _paramIO[paramName]->handleParamAck(ack);
    } else {
        qCritical() << "QGCParamIO is NULL" << paramName;
    }
1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217
}

//-----------------------------------------------------------------------------
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;
    }
1218 1219 1220 1221 1222
    if(_paramIO[paramName]) {
        _paramIO[paramName]->handleParamValue(value);
    } else {
        qCritical() << "QGCParamIO is NULL" << paramName;
    }
1223 1224 1225 1226 1227 1228 1229 1230
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_updateActiveList()
{
    //-- Clear out excluded parameters based on exclusion rules
    QStringList exclusionList;
1231
    for(QGCCameraOptionExclusion* param: _valueExclusions) {
1232 1233 1234 1235 1236 1237 1238 1239
        Fact* pFact = getFact(param->param);
        if(pFact) {
            QString option = pFact->rawValueString();
            if(param->value == option) {
                exclusionList << param->exclusions;
            }
        }
    }
1240
    QStringList active;
1241
    for(QString key: _settings) {
1242
        if(!exclusionList.contains(key)) {
1243
            active.append(key);
1244 1245
        }
    }
1246
    if(active != _activeSettings) {
1247
        qCDebug(CameraControlVerboseLog) << "Excluding" << exclusionList;
1248 1249
        _activeSettings = active;
        emit activeSettingsChanged();
1250 1251 1252 1253
        //-- Force validity of "Facts" based on active set
        if(_paramComplete) {
            emit parametersReady();
        }
1254
    }
1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::_processConditionTest(const QString conditionTest)
{
    enum {
        TEST_NONE,
        TEST_EQUAL,
        TEST_NOT_EQUAL,
        TEST_GREATER,
        TEST_SMALLER
    };
1268
    qCDebug(CameraControlVerboseLog) << "_processConditionTest(" << conditionTest << ")";
1269 1270 1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311
    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)
{
1312
    qCDebug(CameraControlVerboseLog) << "_processCondition(" << condition << ")";
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
    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)
{
1339 1340
    QMap<Fact*, QGCCameraOptionRange*> rangesSet;
    QMap<Fact*, QString> rangesReset;
1341 1342
    QStringList changedList;
    QStringList resetList;
1343
    QStringList updates;
1344
    //-- Iterate range sets looking for limited ranges
1345
    for(QGCCameraOptionRange* pRange: _optionRanges) {
1346 1347 1348 1349 1350
        //-- 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) {
1351
                //qCDebug(CameraControlVerboseLog) << "Check new set of options for" << pTFact->name();
1352 1353
                QString option = pRFact->rawValueString();  //-- This parameter value
                //-- If this value (and condition) triggers a change in the target range
1354
                //qCDebug(CameraControlVerboseLog) << "Range value:" << pRange->value << "Current value:" << option << "Condition:" << pRange->condition;
1355
                if(pRange->value == option && _processCondition(pRange->condition)) {
1356
                    if(pTFact->enumStrings() != pRange->optNames) {
1357 1358
                        //-- Set limited range set
                        rangesSet[pTFact] = pRange;
1359
                    }
1360
                    changedList << pRange->targetParam;
1361 1362 1363 1364 1365
                }
            }
        }
    }
    //-- Iterate range sets again looking for resets
1366
    for(QGCCameraOptionRange* pRange: _optionRanges) {
1367 1368 1369 1370 1371 1372
        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;
1373
                }
1374
                resetList << pRange->targetParam;
1375 1376 1377
            }
        }
    }
1378
    //-- Update limited range set
1379
    for (Fact* f: rangesSet.keys()) {
1380 1381 1382 1383 1384
        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();
1385
            qCDebug(CameraControlVerboseLog) << "Limited set of options for:" << f->name() << rangesSet[f]->optNames;;
1386
            updates << f->name();
1387 1388 1389
        }
    }
    //-- Restore full range set
1390
    for (Fact* f: rangesReset.keys()) {
1391 1392 1393 1394 1395
        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();
1396
            qCDebug(CameraControlVerboseLog) << "Restore full set of options for:" << f->name() << _originalOptNames[f->name()];
1397
            updates << f->name();
1398 1399
        }
    }
1400 1401
    //-- Parameter update requests
    if(_requestUpdates.contains(pFact->name())) {
1402
        for(const QString& param: _requestUpdates[pFact->name()]) {
1403 1404 1405
            if(!_updatesToRequest.contains(param)) {
                _updatesToRequest << param;
            }
1406
        }
1407
    }
1408 1409 1410 1411 1412 1413 1414 1415 1416
    if(_updatesToRequest.size()) {
        QTimer::singleShot(500, this, &QGCCameraControl::_requestParamUpdates);
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestParamUpdates()
{
1417
    for(const QString& param: _updatesToRequest) {
1418 1419 1420
        _paramIO[param]->paramRequest();
    }
    _updatesToRequest.clear();
1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436
}

//-----------------------------------------------------------------------------
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
1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451
//-----------------------------------------------------------------------------
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
    }
}

1452 1453 1454 1455
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
{
Gus Grubba's avatar
Gus Grubba committed
1456
    qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id;
Gus Grubba's avatar
Gus Grubba committed
1457
    _setCameraMode(static_cast<CameraMode>(settings.mode_id));
1458 1459 1460 1461 1462 1463 1464 1465 1466 1467
    qreal z = static_cast<qreal>(settings.zoomLevel);
    qreal f = static_cast<qreal>(settings.focusLevel);
    if(std::isfinite(z) && z != _zoomLevel) {
        _zoomLevel = z;
        emit zoomLevelChanged();
    }
    if(std::isfinite(f) && f != _focusLevel) {
        _focusLevel = f;
        emit focusLevelChanged();
    }
Gus Grubba's avatar
Gus Grubba committed
1468 1469 1470 1471 1472 1473
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st)
{
1474
    qCDebug(CameraControlLog) << "handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity;
1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489
    if(st.status == STORAGE_STATUS_READY) {
        uint32_t t = static_cast<uint32_t>(st.total_capacity);
        if(_storageTotal != t) {
            _storageTotal = t;
            emit storageTotalChanged();
        }
        uint32_t a = static_cast<uint32_t>(st.available_capacity);
        if(_storageFree != a) {
            _storageFree = a;
            emit storageFreeChanged();
        }
    }
    if(_storageStatus != static_cast<StorageStatus>(st.status)) {
        _storageStatus = static_cast<StorageStatus>(st.status);
        emit storageStatusChanged();
Gus Grubba's avatar
Gus Grubba committed
1490 1491 1492 1493 1494 1495 1496 1497 1498 1499
    }
}

//-----------------------------------------------------------------------------
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
Gus Grubba's avatar
Gus Grubba committed
1500 1501 1502
    uint32_t a = static_cast<uint32_t>(cap.available_capacity);
    if(_storageFree != a) {
        _storageFree = a;
Gus Grubba's avatar
Gus Grubba committed
1503 1504
        emit storageFreeChanged();
    }
1505 1506 1507 1508 1509 1510
    //-- Do we have recording time?
    if(cap.recording_time_ms) {
        _recordTime = cap.recording_time_ms;
        _recTime = _recTime.addMSecs(_recTime.elapsed() - static_cast<int>(cap.recording_time_ms));
        emit recordTimeChanged();
    }
1511
    //-- Video/Image Capture Status
Gus Grubba's avatar
Gus Grubba committed
1512 1513 1514 1515
    uint8_t vs = cap.video_status < static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_LAST) ? cap.video_status : static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_UNDEFINED);
    uint8_t ps = cap.image_status < static_cast<uint8_t>(PHOTO_CAPTURE_LAST) ? cap.image_status : static_cast<uint8_t>(PHOTO_CAPTURE_STATUS_UNDEFINED);
    _setVideoStatus(static_cast<VideoStatus>(vs));
    _setPhotoStatus(static_cast<PhotoStatus>(ps));
Gus Grubba's avatar
Gus Grubba committed
1516 1517 1518
    //-- Keep asking for it once in a while when recording
    if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
        _captureStatusTimer.start(5000);
1519 1520
    //-- Same while (single) image capture is busy
    } else if(photoStatus() != PHOTO_CAPTURE_IDLE && photoMode() == PHOTO_CAPTURE_SINGLE) {
1521
        _captureStatusTimer.start(1000);
Gus Grubba's avatar
Gus Grubba committed
1522
    }
1523 1524 1525
    //-- Time Lapse
    if(photoStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) {
        //-- Capture local image as well
1526 1527 1528 1529 1530 1531
        if(qgcApp()->toolbox()->videoManager()->videoReceiver()) {
            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);
        }
1532
    }
1533 1534
}

1535 1536 1537 1538 1539 1540
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi)
{
    qCDebug(CameraControlLog) << "handleVideoInfo:" << vi->stream_id << vi->uri;
    _expectedCount = vi->count;
1541
    if(!_findStream(vi->stream_id, false)) {
1542
        qCDebug(CameraControlLog) << "Create stream handler for stream ID:" << vi->stream_id;
1543 1544 1545
        QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi);
        QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
        _streams.append(pStream);
1546 1547 1548 1549 1550 1551 1552 1553
        //-- Thermal is handled separately and not listed
        if(!pStream->isThermal()) {
            _streamLabels.append(pStream->name());
            emit streamsChanged();
            emit streamLabelsChanged();
        } else {
            emit thermalStreamChanged();
        }
1554 1555 1556 1557 1558 1559
    }
    //-- Check for missing count
    if(_streams.count() < _expectedCount) {
        _streamInfoTimer.start(1000);
    } else {
        //-- Done
1560
        qCDebug(CameraControlLog) << "All stream handlers done";
1561 1562
        _streamInfoTimer.stop();
        emit autoStreamChanged();
1563
        emit _vehicle->dynamicCameras()->streamChanged();
1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs)
{
    _streamStatusTimer.stop();
    qCDebug(CameraControlLog) << "handleVideoStatus:" << vs->stream_id;
    QGCVideoStreamInfo* pInfo = _findStream(vs->stream_id);
    if(pInfo) {
1575
        pInfo->update(vs);
1576 1577 1578 1579 1580 1581 1582
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::setCurrentStream(int stream)
{
1583
    if(stream != _currentStream && stream >= 0 && stream < _streamLabels.count()) {
1584 1585 1586
        if(_currentStream != stream) {
            QGCVideoStreamInfo* pInfo = currentStreamInstance();
            if(pInfo) {
Gus Grubba's avatar
Gus Grubba committed
1587
                qCDebug(CameraControlLog) << "Stopping stream:" << pInfo->uri();
1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598
                //-- Stop current stream
                _vehicle->sendMavCommand(
                    _compID,                                // Target component
                    MAV_CMD_VIDEO_STOP_STREAMING,           // Command id
                    false,                                  // ShowError
                    pInfo->streamID());                     // Stream ID
            }
            _currentStream = stream;
            pInfo = currentStreamInstance();
            if(pInfo) {
                //-- Start new stream
Gus Grubba's avatar
Gus Grubba committed
1599
                qCDebug(CameraControlLog) << "Starting stream:" << pInfo->uri();
1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657
                _vehicle->sendMavCommand(
                    _compID,                                // Target component
                    MAV_CMD_VIDEO_START_STREAMING,          // Command id
                    false,                                  // ShowError
                    pInfo->streamID());                     // Stream ID
                //-- Update stream status
                _requestStreamStatus(static_cast<uint8_t>(pInfo->streamID()));
            }
            emit currentStreamChanged();
            emit _vehicle->dynamicCameras()->streamChanged();
        }
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::stopStream()
{
    QGCVideoStreamInfo* pInfo = currentStreamInstance();
    if(pInfo) {
        //-- Stop current stream
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_VIDEO_STOP_STREAMING,           // Command id
            false,                                  // ShowError
            pInfo->streamID());                     // Stream ID
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::resumeStream()
{
    QGCVideoStreamInfo* pInfo = currentStreamInstance();
    if(pInfo) {
        //-- Start new stream
        _vehicle->sendMavCommand(
            _compID,                                // Target component
            MAV_CMD_VIDEO_START_STREAMING,          // Command id
            false,                                  // ShowError
            pInfo->streamID());                     // Stream ID
    }
}

//-----------------------------------------------------------------------------
bool
QGCCameraControl::autoStream()
{
    if(hasVideoStream()) {
        return _streams.count() > 0;
    }
    return false;
}

//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::currentStreamInstance()
{
1658 1659
    if(_currentStream < _streamLabels.count() && _streamLabels.count()) {
        QGCVideoStreamInfo* pStream = _findStream(_streamLabels[_currentStream]);
1660 1661 1662 1663 1664
        return pStream;
    }
    return nullptr;
}

1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::thermalStreamInstance()
{
    //-- For now, it will return the first thermal listed (if any)
    for(int i = 0; i < _streams.count(); i++) {
        if(_streams[i]) {
            QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
            if(pStream) {
                if(pStream->isThermal()) {
                    return pStream;
                }
            }
        }
    }
    return nullptr;
}

1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStreamInfo(uint8_t streamID)
{
    qCDebug(CameraControlLog) << "Requesting video stream info for:" << streamID;
    _vehicle->sendMavCommand(
        _compID,                                            // Target component
        MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION,           // Command id
        false,                                              // ShowError
        streamID);                                          // Stream ID
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStreamStatus(uint8_t streamID)
{
    qCDebug(CameraControlLog) << "Requesting video stream status for:" << streamID;
    _vehicle->sendMavCommand(
        _compID,                                            // Target component
        MAV_CMD_REQUEST_VIDEO_STREAM_STATUS,                // Command id
        false,                                              // ShowError
        streamID);                                          // Stream ID
    _streamStatusTimer.start(1000);                         // Wait up to a second for it
}

//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
1710
QGCCameraControl::_findStream(uint8_t id, bool report)
1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723
{
    for(int i = 0; i < _streams.count(); i++) {
        if(_streams[i]) {
            QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
            if(pStream) {
                if(pStream->streamID() == id) {
                    return pStream;
                }
            } else {
                qCritical() << "Null QGCVideoStreamInfo instance";
            }
        }
    }
1724 1725 1726
    if(report) {
        qWarning() << "Stream id not found:" << id;
    }
1727 1728 1729
    return nullptr;
}

1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::_findStream(const QString name)
{
    for(int i = 0; i < _streams.count(); i++) {
        if(_streams[i]) {
            QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
            if(pStream) {
                if(pStream->name() == name) {
                    return pStream;
                }
            }
        }
    }
    return nullptr;
}

1747 1748 1749 1750 1751 1752 1753 1754 1755
//-----------------------------------------------------------------------------
void
QGCCameraControl::_streamTimeout()
{
    _requestCount++;
    int count = _expectedCount * 3;
    if(_requestCount > count) {
        qCWarning(CameraControlLog) << "Giving up requesting video stream info";
        _streamInfoTimer.stop();
1756 1757 1758 1759 1760
        //-- If we have at least one stream, work with what we have.
        if(_streams.count()) {
            emit autoStreamChanged();
            emit _vehicle->dynamicCameras()->streamChanged();
        }
1761 1762 1763 1764
        return;
    }
    for(uint8_t i = 0; i < _expectedCount; i++) {
        //-- Stream ID starts at 1
1765
        if(!_findStream(i+1, false)) {
1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781
            _requestStreamInfo(i+1);
            return;
        }
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_streamStatusTimeout()
{
    QGCVideoStreamInfo* pStream = currentStreamInstance();
    if(pStream) {
        _requestStreamStatus(static_cast<uint8_t>(pStream->streamID()));
    }
}

1782 1783 1784 1785 1786 1787 1788 1789
//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadExclusions(QDomNode option)
{
    QStringList exclusionList;
    QDomElement optionElem = option.toElement();
    QDomNodeList excRoot = optionElem.elementsByTagName(kExclusions);
    if(excRoot.size()) {
1790
        //-- Iterate exclusions
1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803
        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;
}

1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825
//-----------------------------------------------------------------------------
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;
}

1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868
//-----------------------------------------------------------------------------
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;
            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);
1869
                qCDebug(CameraControlVerboseLog) << "New range limit:" << factName << paramValue << param << condition << optNames << optValues;
1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880
            }
        }
    }
    return true;
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_processRanges()
{
    //-- After all parameter are loaded, process parameter ranges
1881
    for(QGCCameraOptionRange* pRange: _optionRanges) {
1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920
        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
1921

Gus Grubba's avatar
Gus Grubba committed
1922 1923 1924 1925 1926
//-----------------------------------------------------------------------------
void
QGCCameraControl::_handleDefinitionFile(const QString &url)
{
    //-- First check and see if we have it cached
1927
    QFile xmlFile(_cacheFile);
Gus Grubba's avatar
Gus Grubba committed
1928 1929 1930 1931 1932 1933
    if (!xmlFile.exists()) {
        qCDebug(CameraControlLog) << "No camera definition file cached";
        _httpRequest(url);
        return;
    }
    if (!xmlFile.open(QIODevice::ReadOnly)) {
1934
        qWarning() << "Could not read cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1935 1936 1937 1938 1939 1940
        _httpRequest(url);
        return;
    }
    QByteArray bytes = xmlFile.readAll();
    QDomDocument doc;
    if(!doc.setContent(bytes, false)) {
1941
        qWarning() << "Could not parse cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1942 1943 1944 1945
        _httpRequest(url);
        return;
    }
    //-- We have it
1946
    qCDebug(CameraControlLog) << "Using cached camera definition file:" << _cacheFile;
Gus Grubba's avatar
Gus Grubba committed
1947 1948 1949 1950
    _cached = true;
    emit dataReady(bytes);
}

Gus Grubba's avatar
Gus Grubba committed
1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000
//-----------------------------------------------------------------------------
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);
2001 2002
    } else {
        qCDebug(CameraControlLog) << "No camera definition";
Gus Grubba's avatar
Gus Grubba committed
2003 2004 2005
    }
    _initWhenReady();
}
2006 2007 2008 2009 2010

//-----------------------------------------------------------------------------
void
QGCCameraControl::_paramDone()
{
2011
    for(const QString& param: _paramIO.keys()) {
2012 2013 2014 2015 2016
        if(!_paramIO[param]->paramDone()) {
            return;
        }
    }
    //-- All parameters loaded (or timed out)
2017
    _paramComplete = true;
Gus Grubba's avatar
Gus Grubba committed
2018
    emit parametersReady();
2019 2020 2021 2022 2023 2024 2025 2026 2027
    //-- Check for video streaming
    _checkForVideoStreams();
}

//-----------------------------------------------------------------------------
void
QGCCameraControl::_checkForVideoStreams()
{
    if(_info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) {
2028 2029 2030 2031 2032 2033 2034 2035 2036 2037
        //-- Skip it if using Taisync as it has its own video settings
        if(!qgcApp()->toolbox()->videoManager()->isTaisync()) {
            connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamTimeout);
            _streamInfoTimer.setSingleShot(false);
            connect(&_streamStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_streamStatusTimeout);
            _streamStatusTimer.setSingleShot(true);
            //-- Request all streams
            _requestStreamInfo(0);
            _streamInfoTimer.start(2000);
        }
2038
    }
2039
}
2040 2041 2042 2043 2044 2045 2046 2047 2048

//-----------------------------------------------------------------------------
bool
QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue)
{
    Q_UNUSED(pFact);
    Q_UNUSED(newValue);
    return true;
}
2049 2050 2051 2052 2053 2054 2055 2056 2057

//-----------------------------------------------------------------------------
bool
QGCCameraControl::validateParameter(Fact* pFact, QVariant& newValue)
{
    Q_UNUSED(pFact);
    Q_UNUSED(newValue);
    return true;
}
Gus Grubba's avatar
Gus Grubba committed
2058 2059 2060 2061 2062 2063 2064 2065

//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::activeSettings()
{
    qCDebug(CameraControlLog) << "Active:" << _activeSettings;
    return _activeSettings;
}
2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089

//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::exposureMode()
{
    return (_paramComplete && _activeSettings.contains(kCAM_EXPMODE)) ? getFact(kCAM_EXPMODE) : nullptr;
}

//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::ev()
{
    return (_paramComplete && _activeSettings.contains(kCAM_EV)) ? getFact(kCAM_EV) : nullptr;
}

//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::iso()
{
    return (_paramComplete && _activeSettings.contains(kCAM_ISO)) ? getFact(kCAM_ISO) : nullptr;
}

//-----------------------------------------------------------------------------
Fact*
2090
QGCCameraControl::shutterSpeed()
2091
{
2092
    return (_paramComplete && _activeSettings.contains(kCAM_SHUTTERSPD)) ? getFact(kCAM_SHUTTERSPD) : nullptr;
2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107
}

//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::aperture()
{
    return (_paramComplete && _activeSettings.contains(kCAM_APERTURE)) ? getFact(kCAM_APERTURE) : nullptr;
}

//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::wb()
{
    return (_paramComplete && _activeSettings.contains(kCAM_WBMODE)) ? getFact(kCAM_WBMODE) : nullptr;
}
2108

2109 2110 2111 2112 2113 2114 2115
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::mode()
{
    return _paramComplete ? getFact(kCAM_MODE) : nullptr;
}

2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126
//-----------------------------------------------------------------------------
QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t *si)
    : QObject(parent)
{
    memcpy(&_streamInfo, si, sizeof(mavlink_video_stream_information_t));
}

//-----------------------------------------------------------------------------
qreal
QGCVideoStreamInfo::aspectRatio()
{
Gus Grubba's avatar
Gus Grubba committed
2127
    qreal ar = 1.0;
2128
    if(_streamInfo.resolution_h && _streamInfo.resolution_v) {
Gus Grubba's avatar
Gus Grubba committed
2129
        ar = static_cast<double>(_streamInfo.resolution_h) / static_cast<double>(_streamInfo.resolution_v);
2130
    }
Gus Grubba's avatar
Gus Grubba committed
2131
    return ar;
2132 2133 2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171
}

//-----------------------------------------------------------------------------
bool
QGCVideoStreamInfo::update(const mavlink_video_stream_status_t* vs)
{
    bool changed = false;
    if(_streamInfo.hfov != vs->hfov) {
        changed = true;
        _streamInfo.hfov = vs->hfov;
    }
    if(_streamInfo.flags != vs->flags) {
        changed = true;
        _streamInfo.flags = vs->flags;
    }
    if(_streamInfo.bitrate != vs->bitrate) {
        changed = true;
        _streamInfo.bitrate = vs->bitrate;
    }
    if(_streamInfo.rotation != vs->rotation) {
        changed = true;
        _streamInfo.rotation = vs->rotation;
    }
    if(_streamInfo.framerate != vs->framerate) {
        changed = true;
        _streamInfo.framerate = vs->framerate;
    }
    if(_streamInfo.resolution_h != vs->resolution_h) {
        changed = true;
        _streamInfo.resolution_h = vs->resolution_h;
    }
    if(_streamInfo.resolution_v != vs->resolution_v) {
        changed = true;
        _streamInfo.resolution_v = vs->resolution_v;
    }
    if(changed) {
        emit infoChanged();
    }
    return changed;
}