CameraSection.h 6.32 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10
#pragma once
11

12
#include "Section.h"
13 14 15 16
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "Fact.h"

17 18
#define VIDEO_CAPTURE_STATUS_INTERVAL 0.2   //-- Send capture status every 5 seconds

19
class CameraSection : public Section
20 21 22 23
{
    Q_OBJECT

public:
24
    CameraSection(Vehicle* vehicle, QObject* parent = NULL);
25

DonLakeFlyer's avatar
DonLakeFlyer committed
26 27
    // These enum values must match the json meta data

28 29 30 31
    enum CameraAction {
        CameraActionNone,
        TakePhotosIntervalTime,
        TakePhotoIntervalDistance,
32 33
        StopTakingPhotos,
        TakeVideo,
DonLakeFlyer's avatar
DonLakeFlyer committed
34 35
        StopTakingVideo,
        TakePhoto
36 37
    };
    Q_ENUM(CameraAction)
38 39 40 41 42 43 44

    Q_PROPERTY(bool     specifyGimbal                   READ specifyGimbal                  WRITE setSpecifyGimbal              NOTIFY specifyGimbalChanged)
    Q_PROPERTY(Fact*    gimbalPitch                     READ gimbalPitch                                                        CONSTANT)
    Q_PROPERTY(Fact*    gimbalYaw                       READ gimbalYaw                                                          CONSTANT)
    Q_PROPERTY(Fact*    cameraAction                    READ cameraAction                                                       CONSTANT)
    Q_PROPERTY(Fact*    cameraPhotoIntervalTime         READ cameraPhotoIntervalTime                                            CONSTANT)
    Q_PROPERTY(Fact*    cameraPhotoIntervalDistance     READ cameraPhotoIntervalDistance                                        CONSTANT)
45
    Q_PROPERTY(bool     cameraModeSupported             READ cameraModeSupported                                                CONSTANT)   ///< true: cameraMode is supported by this vehicle
46
    Q_PROPERTY(bool     specifyCameraMode               READ specifyCameraMode              WRITE setSpecifyCameraMode          NOTIFY specifyCameraModeChanged)
47
    Q_PROPERTY(Fact*    cameraMode                      READ cameraMode                                                         CONSTANT)   ///< MAV_CMD_SET_CAMERA_MODE.param2
48 49 50 51 52 53 54

    bool    specifyGimbal               (void) const { return _specifyGimbal; }
    Fact*   gimbalYaw                   (void) { return &_gimbalYawFact; }
    Fact*   gimbalPitch                 (void) { return &_gimbalPitchFact; }
    Fact*   cameraAction                (void) { return &_cameraActionFact; }
    Fact*   cameraPhotoIntervalTime     (void) { return &_cameraPhotoIntervalTimeFact; }
    Fact*   cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; }
55
    bool    cameraModeSupported         (void) const;
56 57
    bool    specifyCameraMode           (void) const { return _specifyCameraMode; }
    Fact*   cameraMode                  (void) { return &_cameraModeFact; }
58

59 60
    void setSpecifyGimbal       (bool specifyGimbal);
    void setSpecifyCameraMode   (bool specifyCameraMode);
61

62
    ///< Signals specifiedGimbalYawChanged
DonLakeFlyer's avatar
DonLakeFlyer committed
63 64 65
    ///< @return The gimbal yaw specified by this item, NaN if not specified
    double specifiedGimbalYaw(void) const;

66 67 68 69
    ///< Signals specifiedGimbalPitchChanged
    ///< @return The gimbal pitch specified by this item, NaN if not specified
    double specifiedGimbalPitch(void) const;

70 71 72 73 74 75 76
    static bool scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex, bool removeScannedItems);
    static bool scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex, bool removeScannedItems);
    static void appendStopTakingPhotos(QList<MissionItem*>& items, int& seqNum, QObject* missionItemParent);
    static void appendStopTakingVideo(QList<MissionItem*>& items, int& seqNum, QObject* missionItemParent);
    static int  stopTakingPhotosCommandCount(void) { return 2; }
    static int  stopTakingVideoCommandCount(void) { return 1; }

77 78 79 80 81
    // Overrides from Section
    bool available          (void) const override { return _available; }
    bool dirty              (void) const override { return _dirty; }
    void setAvailable       (bool available) override;
    void setDirty           (bool dirty) override;
82
    bool scanForSection     (QmlObjectListModel* visualItems, int scanIndex) override;
83 84 85
    void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
    int  itemCount          (void) const override;
    bool settingsSpecified  (void) const override {return _settingsSpecified; }
86 87 88

signals:
    bool specifyGimbalChanged       (bool specifyGimbal);
89
    bool specifyCameraModeChanged   (bool specifyCameraMode);
DonLakeFlyer's avatar
DonLakeFlyer committed
90
    void specifiedGimbalYawChanged  (double gimbalYaw);
91
    void specifiedGimbalPitchChanged(double gimbalPitch);
92 93 94

private slots:
    void _setDirty(void);
95
    void _setDirtyAndUpdateItemCount(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
96
    void _updateSpecifiedGimbalYaw(void);
97
    void _updateSpecifiedGimbalPitch(void);
98
    void _specifyChanged(void);
99 100
    void _updateSettingsSpecified(void);
    void _cameraActionChanged(void);
101
    void _dirtyIfSpecified(void);
102 103

private:
104 105 106
    bool _scanGimbal(QmlObjectListModel* visualItems, int scanIndex);
    bool _scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex);
    bool _scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex);
107 108
    bool _scanTriggerStartDistance(QmlObjectListModel* visualItems, int scanIndex);
    bool _scanTriggerStopDistance(QmlObjectListModel* visualItems, int scanIndex);
109 110 111
    bool _scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex);
    bool _scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex);

112 113 114
    bool    _available;
    bool    _settingsSpecified;
    bool    _specifyGimbal;
115
    bool    _specifyCameraMode;
116 117 118 119 120
    Fact    _gimbalYawFact;
    Fact    _gimbalPitchFact;
    Fact    _cameraActionFact;
    Fact    _cameraPhotoIntervalDistanceFact;
    Fact    _cameraPhotoIntervalTimeFact;
121
    Fact    _cameraModeFact;
122 123 124 125 126 127 128 129 130
    bool    _dirty;

    static QMap<QString, FactMetaData*> _metaDataMap;

    static const char* _gimbalPitchName;
    static const char* _gimbalYawName;
    static const char* _cameraActionName;
    static const char* _cameraPhotoIntervalDistanceName;
    static const char* _cameraPhotoIntervalTimeName;
131
    static const char* _cameraModeName;
132
};