QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleCameraControl.h
Go to the documentation of this file.
1#pragma once
2
5
7class QNetworkAccessManager;
8class QDomNode;
9class QDomNodeList;
10
11//-----------------------------------------------------------------------------
13class QGCCameraOptionExclusion : public QObject
14{
15public:
16 QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_);
17 QString param;
18 QString value;
19 QStringList exclusions;
20};
21
22//-----------------------------------------------------------------------------
24class QGCCameraOptionRange : public QObject
25{
26public:
27 QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_);
28 QString param;
29 QString value;
30 QString targetParam;
31 QString condition;
32 QStringList optNames;
33 QStringList optValues;
34 QVariantList optVariants;
35};
36
39{
40public:
41 VehicleCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = nullptr);
42 virtual ~VehicleCameraControl();
43
44 Q_INVOKABLE virtual void setCameraModeVideo();
45 Q_INVOKABLE virtual void setCameraModePhoto();
46 Q_INVOKABLE virtual void toggleCameraMode ();
47 Q_INVOKABLE virtual bool takePhoto ();
48 Q_INVOKABLE virtual bool stopTakePhoto ();
49 Q_INVOKABLE virtual bool startVideoRecording ();
50 Q_INVOKABLE virtual bool stopVideoRecording ();
51 Q_INVOKABLE virtual bool toggleVideoRecording ();
52 Q_INVOKABLE virtual void resetSettings ();
53 Q_INVOKABLE virtual void formatCard (int id = 1);
54 Q_INVOKABLE virtual void stepZoom (int direction);
55 Q_INVOKABLE virtual void startZoom (int direction);
56 Q_INVOKABLE virtual void stopZoom ();
57 Q_INVOKABLE virtual void stopStream ();
58 Q_INVOKABLE virtual void resumeStream ();
59 Q_INVOKABLE virtual void startTracking (QRectF rec);
60 Q_INVOKABLE virtual void startTracking (QPointF point, double radius);
61 Q_INVOKABLE virtual void stopTracking ();
62
63 virtual int version () const { return _version; }
64 virtual QString modelName () const { return _modelName; }
65 virtual QString vendor () const { return _vendor; }
66 virtual QString firmwareVersion () const;
67 virtual qreal focalLength () const { return static_cast<qreal>(_mavlinkCameraInfo.focal_length); }
68 virtual QSizeF sensorSize () const { return QSizeF(static_cast<qreal>(_mavlinkCameraInfo.sensor_size_h), static_cast<qreal>(_mavlinkCameraInfo.sensor_size_v)); }
69 virtual QSize resolution () const { return QSize(_mavlinkCameraInfo.resolution_h, _mavlinkCameraInfo.resolution_v); }
70 virtual bool capturesVideo () const;
71 virtual bool capturesPhotos () const;
72 virtual bool hasModes () const { return _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_MODES; }
73 virtual bool hasZoom () const { return _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; }
74 virtual bool hasFocus () const { return _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; }
75 virtual bool hasTracking () const { return _trackingStatus & TRACKING_SUPPORTED; }
76 virtual bool hasVideoStream () const { return _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; }
77 virtual bool photosInVideoMode () const { return _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; }
78 virtual bool videoInPhotoMode () const { return _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; }
81
82 virtual int compID () const { return _compID; }
83 virtual bool isBasic () const { return _settings.size() == 0; }
84 virtual StorageStatus storageStatus () const { return _storageStatus; }
85 virtual QStringList activeSettings () const;
86 virtual quint32 storageFree () const { return _storageFree; }
87 virtual QString storageFreeStr () const;
88 virtual quint32 storageTotal () const { return _storageTotal; }
89 virtual int batteryRemaining () const { return _batteryRemaining; }
90 virtual QString batteryRemainingStr () const;
91 virtual bool paramComplete () const { return _paramComplete; }
92 virtual qreal zoomLevel () const { return _zoomLevel; }
93 virtual qreal focusLevel () const { return _focusLevel; }
94
95 virtual QmlObjectListModel* streams () { return &_streams; }
98 virtual int currentStream () const { return _currentStream; }
99 virtual void setCurrentStream (int stream);
100 virtual bool autoStream () const;
101 virtual quint32 recordTime () const { return _recordTime; }
102 virtual QString recordTimeStr () const;
103
104 virtual QStringList streamLabels () const { return _streamLabels; }
105
106 virtual ThermalViewMode thermalMode () const { return _thermalMode; }
107 virtual void setThermalMode (ThermalViewMode mode);
108 virtual double thermalOpacity () const { return _thermalOpacity; }
109 virtual void setThermalOpacity (double val);
110
111 virtual void setZoomLevel (qreal level);
112 virtual void setFocusLevel (qreal level);
113 virtual void setCameraMode(CameraMode cameraMode);
115 virtual void setPhotoLapse (qreal interval);
116 virtual void setPhotoLapseCount (int count);
117
118 virtual void handleCameraSettings(const mavlink_camera_settings_t& settings);
119 virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t& cameraCaptureStatus);
120 virtual void handleParamExtAck (const mavlink_param_ext_ack_t& paramExtAck);
121 virtual void handleParamExtValue (const mavlink_param_ext_value_t& paramExtValue);
122 virtual void handleStorageInformation(const mavlink_storage_information_t& storageInformation);
123 virtual void handleBatteryStatus (const mavlink_battery_status_t& bs);
124 virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus);
125 virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation);
126 virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus);
127
128 virtual bool trackingEnabled () const { return _trackingStatus & TRACKING_ENABLED; }
129 virtual void setTrackingEnabled (bool set);
130
131 virtual TrackingStatus trackingStatus () const { return _trackingStatus; }
132
133 virtual bool trackingImageStatus() const { return _trackingImageStatus.tracking_status == 1; }
134 virtual QRectF trackingImageRect() const { return _trackingImageRect; }
135
136 virtual Fact* exposureMode ();
137 virtual Fact* ev ();
138 virtual Fact* iso ();
139 virtual Fact* shutterSpeed ();
140 virtual Fact* aperture ();
141 virtual Fact* wb ();
142 virtual Fact* mode ();
143 virtual void factChanged (Fact* pFact);
144 virtual bool incomingParameter (Fact* pFact, QVariant& newValue);
145 virtual bool validateParameter (Fact* pFact, QVariant& newValue);
146
147 static constexpr const char* kCondition = "condition";
148 static constexpr const char* kControl = "control";
149 static constexpr const char* kDefault = "default";
150 static constexpr const char* kDefnition = "definition";
151 static constexpr const char* kDescription = "description";
152 static constexpr const char* kExclusion = "exclude";
153 static constexpr const char* kExclusions = "exclusions";
154 static constexpr const char* kLocale = "locale";
155 static constexpr const char* kLocalization = "localization";
156 static constexpr const char* kMax = "max";
157 static constexpr const char* kMin = "min";
158 static constexpr const char* kModel = "model";
159 static constexpr const char* kName = "name";
160 static constexpr const char* kOption = "option";
161 static constexpr const char* kOptions = "options";
162 static constexpr const char* kOriginal = "original";
163 static constexpr const char* kParameter = "parameter";
164 static constexpr const char* kParameterrange = "parameterrange";
165 static constexpr const char* kParameterranges = "parameterranges";
166 static constexpr const char* kParameters = "parameters";
167 static constexpr const char* kReadOnly = "readonly";
168 static constexpr const char* kWriteOnly = "writeonly";
169 static constexpr const char* kRoption = "roption";
170 static constexpr const char* kStep = "step";
171 static constexpr const char* kDecimalPlaces = "decimalPlaces";
172 static constexpr const char* kStrings = "strings";
173 static constexpr const char* kTranslated = "translated";
174 static constexpr const char* kType = "type";
175 static constexpr const char* kUnit = "unit";
176 static constexpr const char* kUpdate = "update";
177 static constexpr const char* kUpdates = "updates";
178 static constexpr const char* kValue = "value";
179 static constexpr const char* kVendor = "vendor";
180 static constexpr const char* kVersion = "version";
181
182 static constexpr const char* kPhotoMode = "PhotoCaptureMode";
183 static constexpr const char* kPhotoLapse = "PhotoLapse";
184 static constexpr const char* kPhotoLapseCount = "PhotoLapseCount";
185 static constexpr const char* kThermalOpacity = "ThermalOpacity";
186 static constexpr const char* kThermalMode = "ThermalMode";
187
188 //-----------------------------------------------------------------------------
189 // Known Parameters
190 static constexpr const char* kCAM_EV = "CAM_EV";
191 static constexpr const char* kCAM_EXPMODE = "CAM_EXPMODE";
192 static constexpr const char* kCAM_ISO = "CAM_ISO";
193 static constexpr const char* kCAM_SHUTTERSPD = "CAM_SHUTTERSPD";
194 static constexpr const char* kCAM_APERTURE = "CAM_APERTURE";
195 static constexpr const char* kCAM_WBMODE = "CAM_WBMODE";
196 static constexpr const char* kCAM_MODE = "CAM_MODE";
197
198protected:
199 virtual void _setVideoCaptureStatus (VideoCaptureStatus captureStatus);
200 virtual void _setPhotoCaptureStatus (PhotoCaptureStatus captureStatus);
201 virtual void _setCameraMode (CameraMode mode);
202 virtual void _requestStreamInfo (uint8_t streamID);
203 virtual void _requestStreamStatus (uint8_t streamID);
204 virtual void _requestTrackingStatus ();
205 virtual QGCVideoStreamInfo* _findStream (uint8_t streamID, bool report = true);
206 virtual QGCVideoStreamInfo* _findStream (const QString name);
207
208protected slots:
209 virtual void _initWhenReady ();
210 virtual void _requestCameraSettings ();
211 virtual void _requestAllParameters ();
212 virtual void _requestParamUpdates ();
213 virtual void _requestCaptureStatus ();
214 virtual void _requestStorageInfo ();
215 virtual void _downloadFinished ();
216 virtual void _mavCommandResult (int vehicleId, int component, int command, int result, int failureCode);
217 virtual void _dataReady (QByteArray data);
218 virtual void _paramDone ();
219 virtual void _streamInfoTimeout ();
220 virtual void _streamStatusTimeout ();
221 virtual void _cameraSettingsTimeout ();
222 virtual void _storageInfoTimeout ();
223 virtual void _recTimerHandler ();
224 virtual void _checkForVideoStreams ();
225 virtual void _onVideoManagerRecordingChanged (bool recording);
226
227private:
228 bool _handleLocalization (QByteArray& bytes);
229 bool _replaceLocaleStrings (const QDomNode node, QByteArray& bytes);
230 bool _loadCameraDefinitionFile (QByteArray& bytes);
231 bool _loadConstants (const QDomNodeList nodeList);
232 bool _loadSettings (const QDomNodeList nodeList);
233 void _processRanges ();
234 bool _processCondition (const QString condition);
235 bool _processConditionTest (const QString conditionTest);
236 bool _loadNameValue (QDomNode option, const QString factName, FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant);
237 bool _loadRanges (QDomNode option, const QString factName, QString paramValue);
238 void _updateActiveList ();
239 void _updateRanges (Fact* pFact);
240 void _httpRequest (const QString& url);
241 void _handleDefinitionFile (const QString& url);
242 void _ftpDownloadComplete (const QString& fileName, const QString& errorMsg);
243
244 QStringList _loadExclusions (QDomNode option);
245 QStringList _loadUpdates (QDomNode option);
246 QString _getParamName (const char* param_id);
247
248protected:
249 int _compID = 0;
250 mavlink_camera_information_t _mavlinkCameraInfo;
251 int _version = 0;
252 bool _cached = false;
253 bool _paramComplete = false;
254 qreal _zoomLevel = 0.0;
255 qreal _focusLevel = 0.0;
256 uint32_t _storageFree = 0;
257 uint32_t _storageTotal = 0;
259 QNetworkAccessManager* _netManager = nullptr;
260 QString _modelName;
261 QString _vendor;
262 QString _cacheFile;
264 QStringList _activeSettings;
265 QStringList _settings;
267 QList<QGCCameraOptionExclusion*> _valueExclusions;
268 QList<QGCCameraOptionRange*> _optionRanges;
269 QMap<QString, QStringList> _originalOptNames;
270 QMap<QString, QVariantList> _originalOptValues;
271 QMap<QString, QGCCameraParamIO*> _paramIO;
276 bool _resetting = false;
277 QTime _recTime;
278 uint32_t _recordTime = 0;
279 //-- Parameters that require a full update
280 QMap<QString, QStringList> _requestUpdates;
281 QStringList _updatesToRequest;
282 //-- Video Streams
293 QStringList _streamLabels;
295 double _thermalOpacity = 85.0;
299 double _trackingRadius = 0.0;
300 mavlink_camera_tracking_image_status_t _trackingImageStatus;
302};
A Fact is used to hold a single value within the system.
Definition Fact.h:19
Abstract base class for all camera controls: real and simulated.
virtual CameraMode cameraMode() const
Camera option exclusions.
Camera option ranges.
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
MAVLink Camera API controller - connected to a real mavlink v2 camera.
virtual QGCVideoStreamInfo * thermalStreamInstance()
static constexpr const char * kCAM_ISO
static constexpr const char * kRoption
virtual bool trackingEnabled() const
static constexpr const char * kName
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)
virtual bool trackingImageStatus() const
QList< QGCCameraOptionRange * > _optionRanges
virtual quint32 recordTime() const
static constexpr const char * kType
virtual CapturePhotosState capturePhotosState() const
static constexpr const char * kModel
virtual QStringList streamLabels() const
Stream names to show the user (for selection)
virtual int version() const
virtual void setPhotoCaptureMode(PhotoCaptureMode mode)
virtual void handleCameraSettings(const mavlink_camera_settings_t &settings)
virtual bool photosInVideoMode() const
mavlink_camera_tracking_image_status_t _trackingImageStatus
virtual bool videoInPhotoMode() const
static constexpr const char * kDescription
virtual void _onVideoManagerRecordingChanged(bool recording)
static constexpr const char * kUpdate
virtual bool hasTracking() const
virtual quint32 storageTotal() const
QmlObjectListModel _streams
virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus)
static constexpr const char * kDecimalPlaces
static constexpr const char * kOptions
virtual bool hasVideoStream() const
virtual void _dataReady(QByteArray data)
virtual QString firmwareVersion() const
virtual QmlObjectListModel * streams()
virtual qreal zoomLevel() const
virtual QString vendor() const
static constexpr const char * kControl
static constexpr const char * kVersion
virtual void setZoomLevel(qreal level)
virtual void setCurrentStream(int stream)
virtual QString recordTimeStr() const
virtual QString storageFreeStr() const
virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation)
virtual bool paramComplete() const
static constexpr const char * kWriteOnly
static constexpr const char * kCAM_EXPMODE
virtual void _cameraSettingsTimeout()
static constexpr const char * kPhotoLapse
virtual void setCameraMode(CameraMode cameraMode)
virtual qreal focalLength() const
static constexpr const char * kCAM_APERTURE
virtual QRectF trackingImageRect() const
virtual void setThermalMode(ThermalViewMode mode)
virtual void stepZoom(int direction)
static constexpr const char * kTranslated
static constexpr const char * kParameterranges
virtual void setFocusLevel(qreal level)
virtual int currentStream() const
virtual bool capturesPhotos() const
static constexpr const char * kUnit
virtual QSizeF sensorSize() const
virtual bool autoStream() const
static constexpr const char * kDefnition
virtual QString modelName() const
static constexpr const char * kVendor
static constexpr const char * kOriginal
QList< QGCCameraOptionExclusion * > _valueExclusions
virtual bool hasFocus() const
virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus)
static constexpr const char * kCAM_SHUTTERSPD
virtual QSize resolution() const
virtual void _requestTrackingStatus()
static constexpr const char * kDefault
static constexpr const char * kMin
virtual bool isBasic() const
virtual void startTracking(QRectF rec)
virtual void _setCameraMode(CameraMode mode)
virtual QGCVideoStreamInfo * currentStreamInstance()
virtual void factChanged(Fact *pFact)
Notify controller a parameter has changed.
virtual ThermalViewMode thermalMode() const
virtual void _requestStreamInfo(uint8_t streamID)
virtual void handleBatteryStatus(const mavlink_battery_status_t &bs)
virtual bool validateParameter(Fact *pFact, QVariant &newValue)
Allow controller to modify or invalidate parameter change.
QMap< QString, QGCCameraParamIO * > _paramIO
static constexpr const char * kPhotoLapseCount
static constexpr const char * kExclusions
static constexpr const char * kLocale
static constexpr const char * kCondition
static constexpr const char * kThermalMode
static constexpr const char * kMax
virtual bool hasModes() const
virtual void _mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
static constexpr const char * kStep
virtual bool incomingParameter(Fact *pFact, QVariant &newValue)
Allow controller to modify or invalidate incoming parameter.
virtual void _requestStreamStatus(uint8_t streamID)
virtual QStringList activeSettings() const
static constexpr const char * kOption
virtual int compID() const
virtual bool toggleVideoRecording()
virtual void formatCard(int id=1)
static constexpr const char * kExclusion
virtual void setThermalOpacity(double val)
virtual quint32 storageFree() const
static constexpr const char * kStrings
QMap< QString, QVariantList > _originalOptValues
virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation)
QMap< QString, QStringList > _originalOptNames
virtual void handleParamExtAck(const mavlink_param_ext_ack_t &paramExtAck)
static constexpr const char * kPhotoMode
static constexpr const char * kReadOnly
virtual void _requestCaptureStatus()
virtual CaptureVideoState captureVideoState() const
virtual double thermalOpacity() const
virtual bool hasZoom() const
virtual bool capturesVideo() const
static constexpr const char * kParameter
virtual int batteryRemaining() const
static constexpr const char * kValue
virtual QGCVideoStreamInfo * _findStream(uint8_t streamID, bool report=true)
static constexpr const char * kUpdates
QMap< QString, QStringList > _requestUpdates
virtual void setPhotoLapse(qreal interval)
static constexpr const char * kParameterrange
static constexpr const char * kParameters
virtual void setPhotoLapseCount(int count)
virtual TrackingStatus trackingStatus() const
virtual void _requestCameraSettings()
static constexpr const char * kCAM_EV
virtual StorageStatus storageStatus() const
QNetworkAccessManager * _netManager
virtual QString batteryRemainingStr() const
virtual void startZoom(int direction)
static constexpr const char * kLocalization
virtual void _setPhotoCaptureStatus(PhotoCaptureStatus captureStatus)
static constexpr const char * kCAM_WBMODE
virtual qreal focusLevel() const
virtual void setTrackingEnabled(bool set)
virtual void handleParamExtValue(const mavlink_param_ext_value_t &paramExtValue)
virtual void _setVideoCaptureStatus(VideoCaptureStatus captureStatus)
mavlink_camera_information_t _mavlinkCameraInfo
static constexpr const char * kCAM_MODE
static constexpr const char * kThermalOpacity