QGCCameraControl.h 7.28 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 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 161 162 163 164 165 166 167 168
/*!
 * @file
 *   @brief Camera Controller
 *   @author Gus Grubba <mavlink@grubba.com>
 *
 */

#pragma once

#include "QGCApplication.h"
#include <QLoggingCategory>

class QDomNode;
class QDomNodeList;
class QGCCameraParamIO;

Q_DECLARE_LOGGING_CATEGORY(CameraControlLog)
Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose)

//-----------------------------------------------------------------------------
class QGCCameraOptionExclusion : public QObject
{
public:
    QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
        : QObject(parent)
        , param(param_)
        , value(value_)
        , exclusions(exclusions_)
    {
    }
    QString param;
    QString value;
    QStringList exclusions;
};

//-----------------------------------------------------------------------------
class QGCCameraOptionRange : public QObject
{
public:
    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_)
    {
    }
    QString param;
    QString value;
    QString targetParam;
    QString condition;
    QStringList  optNames;
    QStringList  optValues;
    QVariantList optVariants;
};

//-----------------------------------------------------------------------------
class QGCCameraControl : public FactGroup
{
    Q_OBJECT
public:
    QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL);
    ~QGCCameraControl();

    //-- cam_mode
    enum CameraMode {
        CAMERA_MODE_UNDEFINED = -1,
        CAMERA_MODE_PHOTO = 0,
        CAMERA_MODE_VIDEO = 1,
    };

    Q_ENUMS(CameraMode)

    Q_PROPERTY(int          version             READ version            NOTIFY infoChanged)
    Q_PROPERTY(QString      modelName           READ modelName          NOTIFY infoChanged)
    Q_PROPERTY(QString      vendor              READ vendor             NOTIFY infoChanged)
    Q_PROPERTY(QString      firmwareVersion     READ firmwareVersion    NOTIFY infoChanged)
    Q_PROPERTY(qreal        focalLength         READ focalLength        NOTIFY infoChanged)
    Q_PROPERTY(QSizeF       sensorSize          READ sensorSize         NOTIFY infoChanged)
    Q_PROPERTY(QSize        resolution          READ resolution         NOTIFY infoChanged)
    Q_PROPERTY(bool         capturesVideo       READ capturesVideo      NOTIFY infoChanged)
    Q_PROPERTY(bool         capturesPhotos      READ capturesPhotos     NOTIFY infoChanged)
    Q_PROPERTY(bool         hasModes            READ hasModes           NOTIFY infoChanged)
    Q_PROPERTY(bool         photosInVideoMode   READ photosInVideoMode  NOTIFY infoChanged)
    Q_PROPERTY(bool         videoInPhotoMode    READ videoInPhotoMode   NOTIFY infoChanged)
    Q_PROPERTY(bool         isBasic             READ isBasic            NOTIFY infoChanged)

    Q_PROPERTY(QStringList  activeSettings      READ activeSettings                             NOTIFY activeSettingsChanged)
    Q_PROPERTY(CameraMode   cameraMode          READ cameraMode         WRITE   setCameraMode   NOTIFY cameraModeChanged)

    Q_INVOKABLE void setVideoMode   ();
    Q_INVOKABLE void setPhotoMode   ();
    Q_INVOKABLE void toggleMode     ();
    Q_INVOKABLE void takePhoto      ();
    Q_INVOKABLE void startVideo     ();
    Q_INVOKABLE void stopVideo      ();
    Q_INVOKABLE void resetSettings  ();
    Q_INVOKABLE void formatCard     (int id = 1);

    int         version             () { return _version; }
    QString     modelName           () { return _modelName; }
    QString     vendor              () { return _vendor; }
    QString     firmwareVersion     ();
    qreal       focalLength         () { return (qreal)_info.focal_length; }
    QSizeF      sensorSize          () { return QSizeF(_info.sensor_size_h, _info.sensor_size_v); }
    QSize       resolution          () { return QSize(_info.resolution_h, _info.resolution_v); }
    bool        capturesVideo       () { return true  /*_info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO*/ ; }
    bool        capturesPhotos      () { return true  /*_info.flags & CAMERA_CAP_FLAGS_CAPTURE_PHOTO*/ ; }
    bool        hasModes            () { return true  /*_info.flags & CAMERA_CAP_FLAGS_HAS_MODES*/ ; }
    bool        photosInVideoMode   () { return true  /*_info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_PHOTO_IN_VIDEO_MODE*/ ; }
    bool        videoInPhotoMode    () { return false /*_info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_PHOTO_MODE*/ ; }

    int         compID              () { return _compID; }
    bool        isBasic             () { return _settings.size() == 0; }
    CameraMode  cameraMode          () { return _cameraMode; }
    QStringList activeSettings      () { return _activeSettings; }

    void        setCameraMode       (CameraMode mode);

    void        handleSettings      (const mavlink_camera_settings_t& settings);
    void        handleParamAck      (const mavlink_param_ext_ack_t& ack);
    void        handleParamValue    (const mavlink_param_ext_value_t& value);
    void        factChanged         (Fact* pFact);

signals:
    void    infoChanged                     ();
    void    cameraModeChanged               ();
    void    activeSettingsChanged           ();

private slots:
    void    _requestCameraSettings          ();
    void    _requestAllParameters           ();

private:
    bool    _handleLocalization             (QByteArray& bytes);
    bool    _replaceLocaleStrings           (const QDomNode node, QByteArray& bytes);
    bool    _loadCameraDefinitionFile       (const QString& file);
    bool    _loadConstants                  (const QDomNodeList nodeList);
    bool    _loadSettings                   (const QDomNodeList nodeList);
    void    _processRanges                  ();
    bool    _processCondition               (const QString condition);
    bool    _processConditionTest           (const QString conditionTest);
    bool    _loadNameValue                  (QDomNode option, const QString factName, FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant);
    bool    _loadRanges                     (QDomNode option, const QString factName, QString paramValue);
    void    _updateActiveList               ();
    void    _updateRanges                   (Fact* pFact);

    QStringList     _loadExclusions         (QDomNode option);
    QString         _getParamName           (const char* param_id);

private:
    Vehicle*                            _vehicle;
    int                                 _compID;
    mavlink_camera_information_t        _info;
    int                                 _version;
    QString                             _modelName;
    QString                             _vendor;
    CameraMode                          _cameraMode;
    QStringList                         _activeSettings;
    QStringList                         _settings;
    QList<QGCCameraOptionExclusion*>    _valueExclusions;
    QList<QGCCameraOptionRange*>        _optionRanges;
    QMap<QString, QStringList>          _originalOptNames;
    QMap<QString, QVariantList>         _originalOptValues;
    QMap<QString, QGCCameraParamIO*>    _paramIO;
};