CameraSection.h 6.37 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * 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 20
class PlanMasterController;

21
class CameraSection : public Section
22 23 24 25
{
    Q_OBJECT

public:
26
    CameraSection(PlanMasterController* masterController, QObject* parent = nullptr);
27

DonLakeFlyer's avatar
DonLakeFlyer committed
28 29
    // These enum values must match the json meta data

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

    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)
47
    Q_PROPERTY(bool     cameraModeSupported             READ cameraModeSupported                                                CONSTANT)   ///< true: cameraMode is supported by this vehicle
48
    Q_PROPERTY(bool     specifyCameraMode               READ specifyCameraMode              WRITE setSpecifyCameraMode          NOTIFY specifyCameraModeChanged)
49
    Q_PROPERTY(Fact*    cameraMode                      READ cameraMode                                                         CONSTANT)   ///< MAV_CMD_SET_CAMERA_MODE.param2
50 51 52 53 54 55 56

    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; }
57
    bool    cameraModeSupported         (void) const;
58 59
    bool    specifyCameraMode           (void) const { return _specifyCameraMode; }
    Fact*   cameraMode                  (void) { return &_cameraModeFact; }
60

61 62
    void setSpecifyGimbal       (bool specifyGimbal);
    void setSpecifyCameraMode   (bool specifyCameraMode);
63

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

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

72 73 74 75 76 77 78
    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; }

79 80 81 82 83
    // 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;
84
    bool scanForSection     (QmlObjectListModel* visualItems, int scanIndex) override;
85 86 87
    void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
    int  itemCount          (void) const override;
    bool settingsSpecified  (void) const override {return _settingsSpecified; }
88 89 90

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

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

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

114 115 116
    bool    _available;
    bool    _settingsSpecified;
    bool    _specifyGimbal;
117
    bool    _specifyCameraMode;
118 119 120 121 122
    Fact    _gimbalYawFact;
    Fact    _gimbalPitchFact;
    Fact    _cameraActionFact;
    Fact    _cameraPhotoIntervalDistanceFact;
    Fact    _cameraPhotoIntervalTimeFact;
123
    Fact    _cameraModeFact;
124 125 126 127 128 129 130 131 132
    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;
133
    static const char* _cameraModeName;
134
};