QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MavlinkCameraControlInterface.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QPointF>
5#include <QtCore/QRectF>
6#include <QtCore/QSizeF>
7
8#include "FactGroup.h"
9
10#include <QtQmlIntegration/QtQmlIntegration>
11
15class Vehicle;
16
20{
21 Q_OBJECT
22 QML_ELEMENT
23 QML_UNCREATABLE("")
24 Q_MOC_INCLUDE("QGCVideoStreamInfo.h")
25 Q_MOC_INCLUDE("QmlObjectListModel.h")
26 Q_PROPERTY(Fact* exposureMode READ exposureMode NOTIFY parametersReady)
27 Q_PROPERTY(Fact* ev READ ev NOTIFY parametersReady)
28 Q_PROPERTY(Fact* iso READ iso NOTIFY parametersReady)
29 Q_PROPERTY(Fact* shutterSpeed READ shutterSpeed NOTIFY parametersReady)
30 Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady)
31 Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady)
32 Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady)
33
34 Q_PROPERTY(int version READ version NOTIFY infoChanged)
35 Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged)
36 Q_PROPERTY(QString vendor READ vendor NOTIFY infoChanged)
37 Q_PROPERTY(QString firmwareVersion READ firmwareVersion NOTIFY infoChanged)
38 Q_PROPERTY(qreal focalLength READ focalLength NOTIFY infoChanged)
39 Q_PROPERTY(QSizeF sensorSize READ sensorSize NOTIFY infoChanged)
40 Q_PROPERTY(QSize resolution READ resolution NOTIFY infoChanged)
41 Q_PROPERTY(bool hasModes READ hasModes NOTIFY infoChanged)
42 Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY infoChanged)
43 Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged)
44 Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged)
45 Q_PROPERTY(bool hasTracking READ hasTracking NOTIFY infoChanged)
47 Q_PROPERTY(bool supportsTrackingRect READ supportsTrackingRect NOTIFY infoChanged)
48 Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged)
49 Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged)
50 Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged)
51
52
54
55 Q_PROPERTY(quint32 storageFree READ storageFree NOTIFY storageFreeChanged)
56 Q_PROPERTY(QString storageFreeStr READ storageFreeStr NOTIFY storageFreeChanged)
57 Q_PROPERTY(quint32 storageTotal READ storageTotal NOTIFY storageTotalChanged)
60 Q_PROPERTY(bool paramComplete READ paramComplete NOTIFY parametersReady)
61 Q_PROPERTY(qreal zoomLevel READ zoomLevel WRITE setZoomLevel NOTIFY zoomLevelChanged)
62 Q_PROPERTY(qreal focusLevel READ focusLevel WRITE setFocusLevel NOTIFY focusLevelChanged)
63 Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
65 Q_PROPERTY(qreal photoLapse READ photoLapse WRITE setPhotoLapse NOTIFY photoLapseChanged)
69 Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged)
70 Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged)
73 Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged)
74 Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged)
75 Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged)
77 Q_PROPERTY(double thermalOpacity READ thermalOpacity WRITE setThermalOpacity NOTIFY thermalOpacityChanged)
78
79 // Camera tracking properties
86
87 // These properties are used to determine what controls to show in the UI and are based on both the camera capabilities as well as the video manager status.
88 // They are not necessarily directly related to the MAVLink camera capabilities.
89 Q_PROPERTY(bool capturesVideo READ capturesVideo NOTIFY infoChanged)
90 Q_PROPERTY(bool capturesPhotos READ capturesPhotos NOTIFY infoChanged)
91
92 // These are "virtual" states which take into account both the mavlink camera capabilities as well as the gstreamer ability to locally record video
93 // as well as to do a photo grab from the video stream. These are what the UI should use to determine what options to present to the user and are updated
94 // based on both the camera info as well as the video manager status.
97
98 friend class QGCCameraParamIO;
99
100public:
101 explicit MavlinkCameraControlInterface(Vehicle *vehicle, QObject *parent = nullptr);
103
110 Q_ENUM(CameraMode)
111
116 Q_ENUM(PhotoCaptureMode)
117
123 Q_ENUM(CaptureVideoState)
124
131 Q_ENUM(CapturePhotosState)
132
134 STORAGE_EMPTY = STORAGE_STATUS_EMPTY,
135 STORAGE_UNFORMATTED = STORAGE_STATUS_UNFORMATTED,
136 STORAGE_READY = STORAGE_STATUS_READY,
137 STORAGE_NOT_SUPPORTED = STORAGE_STATUS_NOT_SUPPORTED
138 };
139 Q_ENUM(StorageStatus)
140
147 Q_ENUM(ThermalViewMode)
148
149
150 Q_INVOKABLE virtual void setCameraModeVideo() = 0;
151 Q_INVOKABLE virtual void setCameraModePhoto() = 0;
152 Q_INVOKABLE virtual void toggleCameraMode() = 0;
153 Q_INVOKABLE virtual bool takePhoto() = 0;
154 Q_INVOKABLE virtual bool stopTakePhoto() = 0;
155 Q_INVOKABLE virtual bool startVideoRecording() = 0;
156 Q_INVOKABLE virtual bool stopVideoRecording() = 0;
157 Q_INVOKABLE virtual bool toggleVideoRecording() = 0;
158 Q_INVOKABLE virtual void resetSettings() = 0;
159 Q_INVOKABLE virtual void formatCard(int id = 1) = 0;
160 Q_INVOKABLE virtual void stepZoom(int direction) = 0;
161 Q_INVOKABLE virtual void startZoom(int direction) = 0;
162 Q_INVOKABLE virtual void stopZoom() = 0;
163 Q_INVOKABLE virtual void stepFocus(int direction) = 0;
164 Q_INVOKABLE virtual void startFocus(int direction) = 0;
165 Q_INVOKABLE virtual void stopFocus() = 0;
166 Q_INVOKABLE virtual void stopStream() = 0;
167 Q_INVOKABLE virtual void resumeStream() = 0;
168 Q_INVOKABLE virtual void startTrackingRect(QRectF rec) = 0;
169 Q_INVOKABLE virtual void startTrackingPoint(QPointF point, double radius) = 0;
170 Q_INVOKABLE virtual void stopTracking() = 0;
171
172 virtual int version() const = 0;
173 virtual QString modelName() const = 0;
174 virtual QString vendor() const = 0;
175 virtual QString firmwareVersion() const = 0;
176 virtual qreal focalLength() const = 0;
177 virtual QSizeF sensorSize() const = 0;
178 virtual QSize resolution() const = 0;
179 virtual bool capturesVideo() const = 0;
180 virtual bool capturesPhotos() const = 0;
181 virtual bool hasModes() const = 0;
182 virtual bool hasZoom() const = 0;
183 virtual bool hasFocus() const = 0;
184 virtual bool hasTracking() const = 0;
185 virtual bool supportsTrackingPoint() const = 0;
186 virtual bool supportsTrackingRect() const = 0;
187 virtual bool hasVideoStream() const = 0;
188 virtual bool photosInVideoMode() const = 0;
189 virtual bool videoInPhotoMode() const = 0;
192
193 virtual int compID() const = 0;
194 virtual bool isBasic() const = 0;
196 virtual qreal photoLapse() const { return _photoLapse; }
197 virtual int photoLapseCount() const { return _photoLapseCount; }
198 virtual CameraMode cameraMode() const { return _cameraMode; }
199 virtual StorageStatus storageStatus() const = 0;
200 virtual QStringList activeSettings() const = 0;
201 virtual quint32 storageFree() const = 0;
202 virtual QString storageFreeStr() const = 0;
203 virtual quint32 storageTotal() const = 0;
204 virtual int batteryRemaining() const = 0;
205 virtual QString batteryRemainingStr() const = 0;
206 virtual bool paramComplete() const = 0;
207 virtual qreal zoomLevel() const = 0;
208 virtual qreal focusLevel() const = 0;
209
213 virtual int currentStream() const = 0;
214 virtual void setCurrentStream(int stream) = 0;
215 virtual bool autoStream() const = 0;
216 virtual quint32 recordTime() const = 0;
217 virtual QString recordTimeStr() const = 0;
218
219 virtual Fact *exposureMode() = 0;
220 virtual Fact *ev() = 0;
221 virtual Fact *iso() = 0;
222 virtual Fact *shutterSpeed() = 0;
223 virtual Fact *aperture() = 0;
224 virtual Fact *wb() = 0;
225 virtual Fact *mode() = 0;
226
227 virtual QStringList streamLabels() const = 0;
228
229 virtual ThermalViewMode thermalMode() const = 0;
231 virtual double thermalOpacity() const = 0;
232 virtual void setThermalOpacity(double val) = 0;
233
234 virtual void setZoomLevel(qreal level) = 0;
235 virtual void setFocusLevel(qreal level) = 0;
238 virtual void setPhotoLapse(qreal interval) = 0;
239 virtual void setPhotoLapseCount(int count) = 0;
240
241 virtual bool trackingEnabled() const = 0;
242 virtual void setTrackingEnabled(bool set) = 0;
243
244 virtual bool trackingImageIsActive() const = 0;
245 virtual bool trackingImageIsPoint() const = 0;
246 virtual QRectF trackingImageRect() const = 0;
247 virtual QPointF trackingImagePoint() const = 0;
248 virtual qreal trackingImageRadius() const = 0;
249
250 virtual void factChanged(Fact *pFact) = 0;
251 virtual bool incomingParameter(Fact *pFact, QVariant &newValue) = 0;
252 virtual bool validateParameter(Fact *pFact, QVariant &newValue) = 0;
253
254 virtual void handleBatteryStatus(const mavlink_battery_status_t &bs) = 0;
255 virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus) = 0;
256 virtual void handleParamExtAck(const mavlink_param_ext_ack_t &paramExtAck) = 0;
257 virtual void handleParamExtValue(const mavlink_param_ext_value_t &paramExtValue) = 0;
258 virtual void handleCameraSettings(const mavlink_camera_settings_t &settings) = 0;
259 virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation) = 0;
260 virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus) = 0;
261 virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation) = 0;
262 virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus) = 0;
263
265 QString captureImageStatusToStr(uint8_t image_status);
266 QString captureVideoStatusToStr(uint8_t video_status);
267 QString storageStatusToStr(uint8_t status);
268
269signals:
281 void dataReady(const QByteArray &data);
302
303protected slots:
304 virtual void _paramDone() = 0;
305
306protected:
313
322
325
326 Vehicle *_vehicle = nullptr;
331 qreal _photoLapse = 1.0;
334};
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
A Fact is used to hold a single value within the system.
Definition Fact.h:17
Abstract base class for all camera controls: real and simulated.
virtual int batteryRemaining() const =0
virtual Q_INVOKABLE void setCameraModePhoto()=0
virtual StorageStatus storageStatus() const =0
virtual QStringList streamLabels() const =0
Stream names to show the user (for selection)
virtual Q_INVOKABLE void stopZoom()=0
virtual Q_INVOKABLE void startZoom(int direction)=0
virtual QGCVideoStreamInfo * thermalStreamInstance()=0
virtual QmlObjectListModel * streams()=0
virtual void setZoomLevel(qreal level)=0
virtual QSize resolution() const =0
virtual QString recordTimeStr() const =0
virtual void handleBatteryStatus(const mavlink_battery_status_t &bs)=0
virtual QString firmwareVersion() const =0
virtual quint32 storageFree() const =0
virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus)=0
virtual Q_INVOKABLE void stepZoom(int direction)=0
virtual void setThermalMode(ThermalViewMode mode)=0
virtual Fact * shutterSpeed()=0
virtual Q_INVOKABLE bool takePhoto()=0
virtual Q_INVOKABLE bool toggleVideoRecording()=0
virtual void setTrackingEnabled(bool set)=0
virtual bool capturesPhotos() const =0
virtual void handleCameraSettings(const mavlink_camera_settings_t &settings)=0
virtual CaptureVideoState captureVideoState() const =0
virtual QString modelName() const =0
virtual QPointF trackingImagePoint() const =0
virtual Q_INVOKABLE void startTrackingRect(QRectF rec)=0
virtual Q_INVOKABLE bool stopVideoRecording()=0
virtual Fact * exposureMode()=0
virtual void setPhotoLapse(qreal interval)=0
virtual QStringList activeSettings() const =0
virtual void setPhotoLapseCount(int count)=0
virtual Q_INVOKABLE void toggleCameraMode()=0
virtual bool trackingImageIsActive() const =0
virtual quint32 storageTotal() const =0
virtual bool capturesVideo() const =0
virtual Q_INVOKABLE void startTrackingPoint(QPointF point, double radius)=0
virtual void factChanged(Fact *pFact)=0
Notify controller a parameter has changed.
virtual qreal trackingImageRadius() const =0
virtual qreal focusLevel() const =0
virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation)=0
PhotoCaptureStatus _photoCaptureStatus() const
virtual bool incomingParameter(Fact *pFact, QVariant &newValue)=0
Allow controller to modify or invalidate incoming parameter.
virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation)=0
virtual Q_INVOKABLE void stepFocus(int direction)=0
virtual QString batteryRemainingStr() const =0
virtual Q_INVOKABLE void startFocus(int direction)=0
virtual PhotoCaptureMode photoCaptureMode() const
virtual QSizeF sensorSize() const =0
virtual qreal focalLength() const =0
virtual bool hasZoom() const =0
virtual void setCameraMode(CameraMode cameraMode)=0
virtual int compID() const =0
virtual Q_INVOKABLE bool stopTakePhoto()=0
virtual void handleParamExtValue(const mavlink_param_ext_value_t &paramExtValue)=0
virtual double thermalOpacity() const =0
virtual Q_INVOKABLE bool startVideoRecording()=0
virtual bool videoInPhotoMode() const =0
virtual Q_INVOKABLE void stopStream()=0
virtual bool hasFocus() const =0
virtual Q_INVOKABLE void formatCard(int id=1)=0
virtual bool supportsTrackingPoint() const =0
virtual void setPhotoCaptureMode(PhotoCaptureMode mode)=0
virtual void setThermalOpacity(double val)=0
QString captureImageStatusToStr(uint8_t image_status)
virtual Q_INVOKABLE void resumeStream()=0
virtual bool paramComplete() const =0
virtual QString vendor() const =0
virtual void setFocusLevel(qreal level)=0
virtual quint32 recordTime() const =0
virtual Q_INVOKABLE void resetSettings()=0
virtual bool supportsTrackingRect() const =0
virtual QGCVideoStreamInfo * currentStreamInstance()=0
virtual bool autoStream() const =0
virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus)=0
virtual bool validateParameter(Fact *pFact, QVariant &newValue)=0
Allow controller to modify or invalidate parameter change.
virtual void setCurrentStream(int stream)=0
virtual int currentStream() const =0
virtual void handleParamExtAck(const mavlink_param_ext_ack_t &paramExtAck)=0
VideoCaptureStatus _videoCaptureStatus() const
virtual qreal zoomLevel() const =0
virtual QRectF trackingImageRect() const =0
virtual bool isBasic() const =0
virtual bool trackingImageIsPoint() const =0
virtual bool hasModes() const =0
virtual bool trackingEnabled() const =0
virtual Fact * aperture()=0
virtual int version() const =0
virtual QString storageFreeStr() const =0
virtual ThermalViewMode thermalMode() const =0
virtual Q_INVOKABLE void stopFocus()=0
virtual Q_INVOKABLE void setCameraModeVideo()=0
virtual bool photosInVideoMode() const =0
virtual CapturePhotosState capturePhotosState() const =0
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)=0
virtual bool hasVideoStream() const =0
virtual bool hasTracking() const =0
virtual Q_INVOKABLE void stopTracking()=0
QString captureVideoStatusToStr(uint8_t video_status)
void dataReady(const QByteArray &data)
Camera parameter handler.
Definition QGCCameraIO.h:14
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.