7class QNetworkAccessManager;
27 QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_);
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 ();
60 Q_INVOKABLE
virtual void startTracking (QPointF point,
double radius);
154 static constexpr const char*
kLocale =
"locale";
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";
170 static constexpr const char*
kStep =
"step";
174 static constexpr const char*
kType =
"type";
175 static constexpr const char*
kUnit =
"unit";
176 static constexpr const char*
kUpdate =
"update";
178 static constexpr const char*
kValue =
"value";
179 static constexpr const char*
kVendor =
"vendor";
182 static constexpr const char*
kPhotoMode =
"PhotoCaptureMode";
190 static constexpr const char*
kCAM_EV =
"CAM_EV";
216 virtual void _mavCommandResult (
int vehicleId,
int component,
int command,
int result,
int failureCode);
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);
244 QStringList _loadExclusions (QDomNode option);
245 QStringList _loadUpdates (QDomNode option);
246 QString _getParamName (
const char* param_id);
A Fact is used to hold a single value within the system.
Abstract base class for all camera controls: real and simulated.
virtual CameraMode cameraMode() const
Camera option exclusions.
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
MAVLink Camera API controller - connected to a real mavlink v2 camera.
virtual void _storageInfoTimeout()
QStringList _updatesToRequest
QRectF _trackingImageRect
virtual QGCVideoStreamInfo * thermalStreamInstance()
static constexpr const char * kCAM_ISO
virtual void _paramDone()
virtual void toggleCameraMode()
virtual void _downloadFinished()
virtual void _streamInfoTimeout()
static constexpr const char * kRoption
virtual void _streamStatusTimeout()
virtual void _requestAllParameters()
virtual bool trackingEnabled() const
QTimer _cameraSettingsTimer
static constexpr const char * kName
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)
virtual bool trackingImageStatus() const
QList< QGCCameraOptionRange * > _optionRanges
virtual bool startVideoRecording()
virtual quint32 recordTime() const
virtual bool stopVideoRecording()
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
virtual Fact * aperture()
static constexpr const char * kDescription
virtual void _checkForVideoStreams()
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)
virtual void _requestStorageInfo()
static constexpr const char * kDecimalPlaces
static constexpr const char * kOptions
virtual bool hasVideoStream() const
virtual void setCameraModeVideo()
virtual void _dataReady(QByteArray data)
virtual QString firmwareVersion() const
virtual QmlObjectListModel * streams()
virtual void _initWhenReady()
virtual Fact * exposureMode()
virtual void _requestParamUpdates()
virtual qreal zoomLevel() const
int _videoStreamInfoRetries
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)
int _videoStreamStatusRetries
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
virtual void resumeStream()
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
virtual void resetSettings()
virtual void setCameraModePhoto()
virtual void stopTracking()
TrackingStatus _trackingStatus
static constexpr const char * kParameterranges
virtual void setFocusLevel(qreal level)
virtual int currentStream() const
virtual bool capturesPhotos() const
ThermalViewMode _thermalMode
QTimer _streamStatusTimer
static constexpr const char * kUnit
virtual QSizeF sensorSize() const
virtual bool autoStream() const
virtual void stopStream()
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()
virtual bool stopTakePhoto()
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.
QStringList _activeSettings
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
QTimer _captureStatusTimer
virtual bool toggleVideoRecording()
virtual void _recTimerHandler()
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 ¶mExtAck)
static constexpr const char * kPhotoMode
QStringList _streamLabels
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 Fact * shutterSpeed()
virtual int batteryRemaining() const
static constexpr const char * kValue
virtual QGCVideoStreamInfo * _findStream(uint8_t streamID, bool report=true)
static constexpr const char * kUpdates
int _cameraCaptureStatusRetries
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
int _cameraSettingsRetries
StorageStatus _storageStatus
virtual StorageStatus storageStatus() const
virtual ~VehicleCameraControl()
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 ¶mExtValue)
virtual void _setVideoCaptureStatus(VideoCaptureStatus captureStatus)
mavlink_camera_information_t _mavlinkCameraInfo
static constexpr const char * kCAM_MODE
static constexpr const char * kThermalOpacity