Skip to content
Snippets Groups Projects
QGCCameraControl.cc 76.9 KiB
Newer Older
  • Learn to ignore specific revisions
  • /*!
     * @file
     *   @brief Camera Controller
     *   @author Gus Grubba <mavlink@grubba.com>
     *
     */
    
    #include "QGCCameraControl.h"
    #include "QGCCameraIO.h"
    
    Gus Grubba's avatar
    Gus Grubba committed
    #include "SettingsManager.h"
    #include "VideoManager.h"
    #include "QGCMapEngine.h"
    
    #include "QGCCameraManager.h"
    
    Gus Grubba's avatar
    Gus Grubba committed
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    #include <QDir>
    
    Gus Grubba's avatar
    Gus Grubba committed
    #include <QStandardPaths>
    
    #include <QDomDocument>
    #include <QDomNodeList>
    
    QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog")
    QGC_LOGGING_CATEGORY(CameraControlLogVerbose, "CameraControlLogVerbose")
    
    
    static const char* kCondition       = "condition";
    
    static const char* kControl         = "control";
    static const char* kDefault         = "default";
    
    static const char* kDefnition       = "definition";
    
    static const char* kDescription     = "description";
    static const char* kExclusion       = "exclude";
    
    static const char* kExclusions      = "exclusions";
    static const char* kLocale          = "locale";
    static const char* kLocalization    = "localization";
    
    static const char* kMax             = "max";
    static const char* kMin             = "min";
    
    static const char* kModel           = "model";
    static const char* kName            = "name";
    static const char* kOption          = "option";
    static const char* kOptions         = "options";
    
    static const char* kOriginal        = "original";
    
    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";
    
    static const char* kWriteOnly       = "writeonly";
    
    static const char* kRoption         = "roption";
    
    static const char* kStep            = "step";
    
    static const char* kDecimalPlaces   = "decimalPlaces";
    
    static const char* kStrings         = "strings";
    
    static const char* kTranslated      = "translated";
    
    static const char* kUnit            = "unit";
    
    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";
    
    static const char* kPhotoMode       = "PhotoMode";
    static const char* kPhotoLapse      = "PhotoLapse";
    static const char* kPhotoLapseCount = "PhotoLapseCount";
    
    
    //-----------------------------------------------------------------------------
    // Known Parameters
    
    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";
    
    Gus Grubba's avatar
    Gus Grubba committed
    //-----------------------------------------------------------------------------
    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_)
    {
    }
    
    
    //-----------------------------------------------------------------------------
    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)
    {
    
        QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
    
        memcpy(&_info, info, sizeof(mavlink_camera_information_t));
    
    Gus Grubba's avatar
    Gus Grubba committed
        connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
    
    Gus Grubba's avatar
    Gus Grubba committed
        _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);
    
        _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
        if(info->cam_definition_uri[0] != 0) {
    
    Gus Grubba's avatar
    Gus Grubba committed
            //-- Process camera definition file
    
    Gus Grubba's avatar
    Gus Grubba committed
            _handleDefinitionFile(info->cam_definition_uri);
    
    Gus Grubba's avatar
    Gus Grubba committed
        } else {
            _initWhenReady();
        }
    
        QSettings settings;
    
    Gus Grubba's avatar
    Gus Grubba committed
        _photoMode  = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
    
        _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
        _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
    
        _recTimer.setSingleShot(false);
        _recTimer.setInterval(333);
        connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler);
    
    }
    
    //-----------------------------------------------------------------------------
    QGCCameraControl::~QGCCameraControl()
    {
    
    Gus Grubba's avatar
    Gus Grubba committed
        if(_netManager) {
            delete _netManager;
        }
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::_initWhenReady()
    {
        qCDebug(CameraControlLog) << "_initWhenReady()";
        if(isBasic()) {
            qCDebug(CameraControlLog) << "Basic, MAVLink only messages.";
            _requestCameraSettings();
    
            QTimer::singleShot(250, this, &QGCCameraControl::_checkForVideoStreams);
    
    Gus Grubba's avatar
    Gus Grubba committed
        } 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
            _netManager = nullptr;
    
    Gus Grubba's avatar
    Gus Grubba committed
        }
    
    }
    
    //-----------------------------------------------------------------------------
    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;
    }
    
    
    //-----------------------------------------------------------------------------
    QString
    QGCCameraControl::recordTimeStr()
    {
        return QTime(0, 0).addMSecs(static_cast<int>(recordTime())).toString("hh:mm:ss");
    }
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    //-----------------------------------------------------------------------------
    QGCCameraControl::VideoStatus
    QGCCameraControl::videoStatus()
    {
        return _video_status;
    }
    
    
    //-----------------------------------------------------------------------------
    QGCCameraControl::PhotoStatus
    QGCCameraControl::photoStatus()
    {
        return _photo_status;
    }
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    //-----------------------------------------------------------------------------
    QString
    QGCCameraControl::storageFreeStr()
    {
    
        return QGCMapEngine::bigSizeToString(static_cast<quint64>(_storageFree) * 1024 * 1024);
    
    Gus Grubba's avatar
    Gus Grubba committed
    }
    
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::setCameraMode(CameraMode mode)
    {
    
        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;
    
    Gus Grubba's avatar
    Gus Grubba committed
    }
    
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::setPhotoMode(PhotoMode mode)
    {
    
        if(!_resetting) {
            _photoMode = mode;
            QSettings settings;
            settings.setValue(kPhotoMode, static_cast<int>(mode));
            emit photoModeChanged();
        }
    
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::setPhotoLapse(qreal interval)
    {
        _photoLapse = interval;
        QSettings settings;
        settings.setValue(kPhotoLapse, interval);
        emit photoLapseChanged();
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::setPhotoLapseCount(int count)
    {
        _photoLapseCount = count;
        QSettings settings;
        settings.setValue(kPhotoLapseCount, count);
        emit photoLapseCountChanged();
    }
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::_setCameraMode(CameraMode mode)
    {
    
        if(_cameraMode != mode) {
            _cameraMode = mode;
            emit cameraModeChanged();
            //-- Update stream status
            _streamStatusTimer.start(1000);
        }
    
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::toggleMode()
    {
    
        if(!_resetting) {
            if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) {
                setVideoMode();
            } else if(cameraMode() == CAM_MODE_VIDEO) {
                setPhotoMode();
            }
    
        }
    }
    
    //-----------------------------------------------------------------------------
    
    Gus Grubba's avatar
    Gus Grubba committed
    bool
    QGCCameraControl::toggleVideo()
    
        if(!_resetting) {
            if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
                return stopVideo();
            } else {
                return startVideo();
            }
    
    Gus Grubba's avatar
    Gus Grubba committed
        }
    
    Gus Grubba's avatar
    Gus Grubba committed
    }
    
    Gus Grubba's avatar
    Gus Grubba committed
    //-----------------------------------------------------------------------------
    bool
    QGCCameraControl::takePhoto()
    {
        qCDebug(CameraControlLog) << "takePhoto()";
        //-- Check if camera can capture photos or if it can capture it while in Video Mode
    
        if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) {
    
    Gus Grubba's avatar
    Gus Grubba committed
            return false;
        }
    
        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
                QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
                QDir().mkpath(photoPath);
                photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
                qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath);
                return true;
            }
    
    Gus Grubba's avatar
    Gus Grubba committed
        }
        return false;
    
    //-----------------------------------------------------------------------------
    bool
    QGCCameraControl::stopTakePhoto()
    {
    
        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;
            }
    
        }
        return false;
    }
    
    
    //-----------------------------------------------------------------------------
    
    Gus Grubba's avatar
    Gus Grubba committed
    bool
    
    QGCCameraControl::startVideo()
    {
    
        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
    
                    false,                                      // Don't Show Error (handle locally)
    
                    0,                                          // Reserved (Set to 0)
                    0);                                         // CAMERA_CAPTURE_STATUS Frequency
                return true;
            }
    
    Gus Grubba's avatar
    Gus Grubba committed
        }
        return false;
    
    }
    
    //-----------------------------------------------------------------------------
    
    Gus Grubba's avatar
    Gus Grubba committed
    bool
    
    QGCCameraControl::stopVideo()
    {
    
        if(!_resetting) {
            qCDebug(CameraControlLog) << "stopVideo()";
            if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
                _vehicle->sendMavCommand(
                    _compID,                                    // Target component
                    MAV_CMD_VIDEO_STOP_CAPTURE,                 // Command id
    
                    false,                                      // Don't Show Error (handle locally)
    
                    0);                                         // Reserved (Set to 0)
                return true;
            }
    
    Gus Grubba's avatar
    Gus Grubba committed
        }
        return false;
    
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::setVideoMode()
    {
    
        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);
                }
    
        }
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::setPhotoMode()
    {
    
        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);
                }
    
    //-----------------------------------------------------------------------------
    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
            }
        }
    }
    
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::resetSettings()
    {
    
        if(!_resetting) {
            qCDebug(CameraControlLog) << "resetSettings()";
            _resetting = true;
            _vehicle->sendMavCommand(
                _compID,                                // Target component
                MAV_CMD_RESET_CAMERA_SETTINGS,          // Command id
                true,                                   // ShowError
                1);                                     // Do Reset
        }
    
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::formatCard(int id)
    {
    
        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
            }
    
    //-----------------------------------------------------------------------------
    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
                true,                                   // ShowError
                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
                true,                                   // ShowError
                ZOOM_TYPE_CONTINUOUS,                   // Zoom type
                0);                                     // Direction (-1 wide, 1 tele)
        }
    }
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::_requestCaptureStatus()
    {
    
        qCDebug(CameraControlLog) << "_requestCaptureStatus()";
    
    Gus Grubba's avatar
    Gus Grubba committed
        _vehicle->sendMavCommand(
            _compID,                                // target component
            MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS,  // command id
            false,                                  // showError
            1);                                     // Do Request
    }
    
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::factChanged(Fact* pFact)
    {
        _updateActiveList();
        _updateRanges(pFact);
    }
    
    //-----------------------------------------------------------------------------
    
    Gus Grubba's avatar
    Gus Grubba committed
    void
    QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle)
    
    Gus Grubba's avatar
    Gus Grubba committed
        //-- Is this ours?
        if(_vehicle->id() != vehicleId || compID() != component) {
            return;
        }
    
        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
            switch(command) {
                case MAV_CMD_RESET_CAMERA_SETTINGS:
    
    Gus Grubba's avatar
    Gus Grubba committed
                    if(isBasic()) {
                        _requestCameraSettings();
                    } else {
    
                        QTimer::singleShot(500, this, &QGCCameraControl::_requestAllParameters);
                        QTimer::singleShot(2500, this, &QGCCameraControl::_requestCameraSettings);
    
    Gus Grubba's avatar
    Gus Grubba committed
                    }
                    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);
    
                    _captureStatusTimer.start(1000);
    
    Gus Grubba's avatar
    Gus Grubba committed
                    break;
    
                case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
                    _captureInfoRetries = 0;
                    break;
                case MAV_CMD_REQUEST_STORAGE_INFORMATION:
                    _storageInfoRetries = 0;
                    break;
    
    Gus Grubba's avatar
    Gus Grubba committed
            }
    
    Gus Grubba's avatar
    Gus Grubba committed
        } else {
    
            if(noReponseFromVehicle || result == MAV_RESULT_TEMPORARILY_REJECTED || result == MAV_RESULT_FAILED) {
                if(noReponseFromVehicle) {
                    qCDebug(CameraControlLog) << "No response for" << command;
                } else if (result == MAV_RESULT_TEMPORARILY_REJECTED) {
                    qCDebug(CameraControlLog) << "Command temporarily rejected for" << command;
                } else {
                    qCDebug(CameraControlLog) << "Command failed for" << command;
                }
                switch(command) {
    
                    case MAV_CMD_IMAGE_START_CAPTURE:
    
                    case MAV_CMD_IMAGE_STOP_CAPTURE:
    
                        if(++_captureInfoRetries < 5) {
                            _captureStatusTimer.start(1000);
                        } else {
                            qCDebug(CameraControlLog) << "Giving up requesting capture status";
                        }
                        break;
    
                    case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
                        if(++_captureInfoRetries < 3) {
    
                            _captureStatusTimer.start(500);
    
                        } else {
                            qCDebug(CameraControlLog) << "Giving up requesting capture status";
                        }
                        break;
                    case MAV_CMD_REQUEST_STORAGE_INFORMATION:
                        if(++_storageInfoRetries < 3) {
    
                            QTimer::singleShot(500, this, &QGCCameraControl::_requestStorageInfo);
    
                        } else {
                            qCDebug(CameraControlLog) << "Giving up requesting storage status";
                        }
                        break;
                }
    
    Gus Grubba's avatar
    Gus Grubba committed
            } else {
    
                qCDebug(CameraControlLog) << "Bad response for" << command << result;
    
    Gus Grubba's avatar
    Gus Grubba committed
            }
    
    Gus Grubba's avatar
    Gus Grubba committed
        }
    }
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::_setVideoStatus(VideoStatus status)
    {
        if(_video_status != status) {
            _video_status = status;
            emit videoStatusChanged();
    
            if(status == VIDEO_CAPTURE_STATUS_RUNNING) {
                 _recordTime = 0;
                 _recTime.start();
                 _recTimer.start();
            } else {
                 _recTimer.stop();
                 _recordTime = 0;
                 emit recordTimeChanged();
            }
    
    Gus Grubba's avatar
    Gus Grubba committed
    }
    
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::_recTimerHandler()
    {
        _recordTime = static_cast<uint32_t>(_recTime.elapsed());
        emit recordTimeChanged();
    }
    
    
    //-----------------------------------------------------------------------------
    void
    QGCCameraControl::_setPhotoStatus(PhotoStatus status)
    {
        if(_photo_status != status) {
            _photo_status = status;
            emit photoStatusChanged();
        }
    }
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    //-----------------------------------------------------------------------------
    bool
    QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
    {
    
    Gus Grubba's avatar
    Gus Grubba committed
        QByteArray originalData(bytes);
    
        //-- 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
            qWarning() <<  "Unable to load camera constants from camera definition";
    
            return false;
        }
        //-- Load camera parameters
        QDomNodeList paramElements = doc.elementsByTagName(kParameters);
        if(!paramElements.size() || !_loadSettings(paramElements)) {
    
    Gus Grubba's avatar
    Gus Grubba committed
            qWarning() <<  "Unable to load camera parameters from camera definition";
    
            return false;
        }
    
    Gus Grubba's avatar
    Gus Grubba committed
        //-- If this is new, cache it
        if(!_cached) {
    
            qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile;
            QFile file(_cacheFile);
    
    Gus Grubba's avatar
    Gus Grubba committed
            if (!file.open(QIODevice::WriteOnly)) {
    
                qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString());
    
    Gus Grubba's avatar
    Gus Grubba committed
            } else {
                file.write(originalData);
            }
        }
    
        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;
            }
    
            //-- 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);
    
            //-- 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);
            }
    
            //-- Param type
    
            bool unknownType;
            FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
            if (unknownType) {
                qCritical() << QString("Unknown type for parameter %1").arg(factName);
                return false;
            }
    
            //-- By definition, custom types do not have control
            if(factType == FactMetaData::valueTypeCustom) {
                control = false;
            }
    
            //-- Description
    
            QString description;
            if(!read_value(parameterNode, kDescription, description)) {
                qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
                return false;
            }
    
            //-- Check for updates
            QStringList updates = _loadUpdates(parameterNode);
            if(updates.size()) {
                qCDebug(CameraControlLogVerbose) << "Parameter" << factName << "requires updates for:" << updates;
                _requestUpdates[factName] = updates;
    
            //-- Build metadata
            FactMetaData* metaData = new FactMetaData(factType, factName, this);
    
            QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
    
            metaData->setShortDescription(description);
            metaData->setLongDescription(description);
    
            metaData->setHasControl(control);
            metaData->setReadOnly(readOnly);
    
            metaData->setWriteOnly(writeOnly);
    
            //-- Options (enums)
            QDomElement optionElem = parameterNode.toElement();
            QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions);
            if(optionsRoot.size()) {
                //-- Iterate options
                QDomNode node = optionsRoot.item(0);
                QDomElement elem = node.toElement();
                QDomNodeList options = elem.elementsByTagName(kOption);
                for(int i = 0; i < options.size(); i++) {
                    QDomNode option = options.item(i);
                    QString optName;
                    QString optValue;
                    QVariant optVariant;
                    if(!_loadNameValue(option, factName, metaData, optName, optValue, optVariant)) {
                        delete metaData;
                        return false;
                    }
                    metaData->addEnumInfo(optName, optVariant);
                    _originalOptNames[factName]  << optName;
                    _originalOptValues[factName] << optVariant;
                    //-- Check for exclusions
                    QStringList exclusions = _loadExclusions(option);
                    if(exclusions.size()) {
                        qCDebug(CameraControlLogVerbose) << "New exclusions:" << factName << optValue << exclusions;
                        QGCCameraOptionExclusion* pExc = new QGCCameraOptionExclusion(this, factName, optValue, exclusions);
    
                        QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
    
                        _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 {
    
                {
                    //-- 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)) {
    
                            metaData->setRawIncrement(typedValue.toDouble());
    
                        } else {
                            qWarning() << "Invalid step value for" << factName
                                       << " type:"  << metaData->type()
                                       << " value:" << attr
                                       << " error:" << errorString;
                        }
                    }
                }
    
                {
                    //-- 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;
                        }
                    }
                }