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