QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
CameraSection.h
Go to the documentation of this file.
1#pragma once
2
3#include "Section.h"
4#include "Fact.h"
5
6#define VIDEO_CAPTURE_STATUS_INTERVAL 0.2 //-- Send capture status every 5 seconds
7
9class CameraSectionTest;
10class MissionItem;
12
13
14class CameraSection : public Section
15{
16 Q_OBJECT
17
18public:
19 CameraSection(PlanMasterController* masterController, QObject* parent = nullptr);
20
21 // These enum values must match the json meta data
22
32 Q_ENUM(CameraAction)
33
34 Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged)
35 Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
36 Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT)
37 Q_PROPERTY(Fact* cameraAction READ cameraAction CONSTANT)
40 Q_PROPERTY(bool cameraModeSupported READ cameraModeSupported CONSTANT)
42 Q_PROPERTY(Fact* cameraMode READ cameraMode CONSTANT)
43
44 bool specifyGimbal (void) const { return _specifyGimbal; }
45 Fact* gimbalYaw (void) { return &_gimbalYawFact; }
46 Fact* gimbalPitch (void) { return &_gimbalPitchFact; }
47 Fact* cameraAction (void) { return &_cameraActionFact; }
48 Fact* cameraPhotoIntervalTime (void) { return &_cameraPhotoIntervalTimeFact; }
49 Fact* cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; }
50 bool cameraModeSupported (void) const;
51 bool specifyCameraMode (void) const { return _specifyCameraMode; }
52 Fact* cameraMode (void) { return &_cameraModeFact; }
53
54 void setSpecifyGimbal (bool specifyGimbal);
56
58 double specifiedGimbalYaw(void) const;
59
61 double specifiedGimbalPitch(void) const;
62
63 static bool scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex, bool removeScannedItems);
64 static bool scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex, bool removeScannedItems);
65 static void appendStopTakingPhotos(QList<MissionItem*>& items, int& seqNum, QObject* missionItemParent);
66 static void appendStopTakingVideo(QList<MissionItem*>& items, int& seqNum, QObject* missionItemParent);
67 static int stopTakingPhotosCommandCount(void) { return 2; }
68 static int stopTakingVideoCommandCount(void) { return 1; }
69
70 // Overrides from Section
71 bool available (void) const override { return _available; }
72 bool dirty (void) const override { return _dirty; }
73 void setAvailable (bool available) override;
74 void setDirty (bool dirty) override;
75 bool scanForSection (QmlObjectListModel* visualItems, int scanIndex) override;
76 void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
77 int itemCount (void) const override;
78 bool settingsSpecified (void) const override {return _settingsSpecified; }
79
80signals:
81 bool specifyGimbalChanged (bool specifyGimbal);
85
86private slots:
87 void _setDirty(void);
88 void _setDirtyAndUpdateItemCount(void);
89 void _updateSpecifiedGimbalYaw(void);
90 void _updateSpecifiedGimbalPitch(void);
91 void _specifyChanged(void);
92 void _updateSettingsSpecified(void);
93 void _cameraActionChanged(void);
94 void _dirtyIfSpecified(void);
95
96private:
97 bool _scanGimbal(QmlObjectListModel* visualItems, int scanIndex);
98 bool _scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex);
99 bool _scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex);
100 bool _scanTriggerStartDistance(QmlObjectListModel* visualItems, int scanIndex);
101 bool _scanTriggerStopDistance(QmlObjectListModel* visualItems, int scanIndex);
102 bool _scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex);
103 bool _scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex);
104
105 bool _available;
106 bool _settingsSpecified;
107 bool _specifyGimbal;
108 bool _specifyCameraMode;
109 Fact _gimbalYawFact;
110 Fact _gimbalPitchFact;
111 Fact _cameraActionFact;
112 Fact _cameraPhotoIntervalDistanceFact;
113 Fact _cameraPhotoIntervalTimeFact;
114 Fact _cameraModeFact;
115 int _takePhotoSequence;
116 bool _dirty;
117
118 static QMap<QString, FactMetaData*> _metaDataMap;
119
120 static constexpr const char* _gimbalPitchName = "GimbalPitch";
121 static constexpr const char* _gimbalYawName = "GimbalYaw";
122 static constexpr const char* _cameraActionName = "CameraAction";
123 static constexpr const char* _cameraPhotoIntervalDistanceName = "CameraPhotoIntervalDistance";
124 static constexpr const char* _cameraPhotoIntervalTimeName = "CameraPhotoIntervalTime";
125 static constexpr const char* _cameraModeName = "CameraMode";
126
127 friend CameraSectionTest;
128};
void setSpecifyCameraMode(bool specifyCameraMode)
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override
double specifiedGimbalPitch(void) const
void setSpecifyGimbal(bool specifyGimbal)
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
bool specifyCameraMode(void) const
bool settingsSpecified(void) const override
void specifiedGimbalYawChanged(double gimbalYaw)
bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged(Fact *gimbalPitch READ gimbalPitch CONSTANT) 1(Fact *gimbalYaw READ gimbalYaw CONSTANT) 1(Fact *cameraAction READ cameraAction CONSTANT) 1(Fact *cameraPhotoIntervalTime READ cameraPhotoIntervalTime CONSTANT) 1(Fact *cameraPhotoIntervalDistance READ cameraPhotoIntervalDistance CONSTANT) 1(bool cameraModeSupported READ cameraModeSupported CONSTANT) 1(bool specifyCameraMode READ specifyCameraMode WRITE setSpecifyCameraMode NOTIFY specifyCameraModeChanged) 1(Fact *cameraMode READ cameraMode CONSTANT) bool specifyGimbal(void) const
< true: cameraMode is supported by this vehicle
static int stopTakingPhotosCommandCount(void)
double specifiedGimbalYaw(void) const
Fact * gimbalPitch(void)
static void appendStopTakingVideo(QList< MissionItem * > &items, int &seqNum, QObject *missionItemParent)
Fact * cameraPhotoIntervalTime(void)
Fact * cameraMode(void)
bool cameraModeSupported(void) const
Fact * gimbalYaw(void)
void specifiedGimbalPitchChanged(double gimbalPitch)
static void appendStopTakingPhotos(QList< MissionItem * > &items, int &seqNum, QObject *missionItemParent)
bool specifyGimbalChanged(bool specifyGimbal)
static bool scanStopTakingVideo(QmlObjectListModel *visualItems, int scanIndex, bool removeScannedItems)
static int stopTakingVideoCommandCount(void)
static bool scanStopTakingPhotos(QmlObjectListModel *visualItems, int scanIndex, bool removeScannedItems)
Fact * cameraPhotoIntervalDistance(void)
bool dirty(void) const override
bool available(void) const override
bool specifyCameraModeChanged(bool specifyCameraMode)
int itemCount(void) const override
Fact * cameraAction(void)
void setDirty(bool dirty) override
void setAvailable(bool available) override
A Fact is used to hold a single value within the system.
Definition Fact.h:19
Master controller for mission, fence, rally.