3#include <QtCore/QObject>
4#include <QtCore/QPointF>
5#include <QtCore/QRectF>
6#include <QtCore/QSizeF>
10#include <QtQmlIntegration/QtQmlIntegration>
23 Q_MOC_INCLUDE(
"QGCVideoStreamInfo.h")
24 Q_MOC_INCLUDE(
"QmlObjectListModel.h")
159 Q_INVOKABLE virtual
void stepZoom(
int direction) = 0;
Used to group Facts together into an object hierarachy.
A Fact is used to hold a single value within the system.
Abstract base class for all camera controls: real and simulated.
virtual int batteryRemaining() const =0
virtual StorageStatus storageStatus() const =0
virtual QStringList streamLabels() const =0
Stream names to show the user (for selection)
virtual void formatCard(int id=1)=0
virtual void setCameraModePhoto()=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 void resumeStream()=0
virtual void setThermalMode(ThermalViewMode mode)=0
virtual Fact * shutterSpeed()=0
virtual void setTrackingEnabled(bool set)=0
virtual void setCameraModeVideo()=0
void trackingImageRadiusChanged()
virtual bool capturesPhotos() const =0
virtual void handleCameraSettings(const mavlink_camera_settings_t &settings)=0
virtual CaptureVideoState captureVideoState() const =0
virtual void stopStream()=0
virtual QString modelName() const =0
virtual void stopTracking()=0
virtual QPointF trackingImagePoint() const =0
@ CapturePhotosStateDisabled
@ CapturePhotosStateCapturingSinglePhoto
@ CapturePhotosStateCapturingMultiplePhotos
void trackingImageIsPointChanged()
virtual Fact * exposureMode()=0
@ PHOTO_CAPTURE_INTERVAL_IDLE
@ PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
@ PHOTO_CAPTURE_IN_PROGRESS
@ PHOTO_CAPTURE_STATUS_UNDEFINED
void batteryRemainingChanged()
virtual void setPhotoLapse(qreal interval)=0
virtual QStringList activeSettings() const =0
virtual bool startVideoRecording()=0
virtual bool stopVideoRecording()=0
virtual void setPhotoLapseCount(int count)=0
virtual bool trackingImageIsActive() const =0
virtual quint32 storageTotal() const =0
void photoLapseCountChanged()
virtual bool capturesVideo() const =0
virtual void factChanged(Fact *pFact)=0
Notify controller a parameter has changed.
virtual bool stopTakePhoto()=0
virtual qreal trackingImageRadius() const =0
virtual qreal focusLevel() const =0
void videoCaptureStatusChanged()
void storageFreeChanged()
virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation)=0
virtual void stepFocus(int direction)=0
PhotoCaptureStatus _photoCaptureStatus() const
virtual void toggleCameraMode()=0
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
QString storageStatusToStr(uint8_t status)
PhotoCaptureMode _photoCaptureMode
virtual QString batteryRemainingStr() const =0
void storageStatusChanged()
QString cameraModeToStr(CameraMode mode)
virtual PhotoCaptureMode photoCaptureMode() const
virtual QSizeF sensorSize() const =0
virtual qreal focalLength() const =0
virtual bool hasZoom() const =0
virtual void startTrackingRect(QRectF rec)=0
virtual void setCameraMode(CameraMode cameraMode)=0
virtual bool takePhoto()=0
virtual int compID() const =0
virtual void handleParamExtValue(const mavlink_param_ext_value_t ¶mExtValue)=0
virtual double thermalOpacity() const =0
virtual void stopFocus()=0
virtual bool videoInPhotoMode() const =0
virtual bool hasFocus() const =0
virtual void stopZoom()=0
void photoCaptureStatusChanged()
virtual bool supportsTrackingPoint() const =0
virtual void setPhotoCaptureMode(PhotoCaptureMode mode)=0
virtual void setThermalOpacity(double val)=0
QString captureImageStatusToStr(uint8_t image_status)
virtual qreal photoLapse() const
virtual bool paramComplete() const =0
virtual QString vendor() const =0
virtual void stepZoom(int direction)=0
virtual void setFocusLevel(qreal level)=0
VideoCaptureStatus _videoCaptureStatusValue
virtual quint32 recordTime() const =0
void trackingEnabledChanged()
virtual bool supportsTrackingRect() const =0
virtual void startFocus(int direction)=0
void storageTotalChanged()
void activeSettingsChanged()
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 ¶mExtAck)=0
VideoCaptureStatus _videoCaptureStatus() const
void capturePhotosStateChanged()
@ VIDEO_CAPTURE_STATUS_UNDEFINED
@ VIDEO_CAPTURE_STATUS_STOPPED
@ VIDEO_CAPTURE_STATUS_LAST
@ VIDEO_CAPTURE_STATUS_RUNNING
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
void trackingImageRectChanged()
virtual void startTrackingPoint(QPointF point, double radius)=0
void captureVideoStateChanged()
void trackingImageIsActiveChanged()
virtual bool trackingEnabled() const =0
virtual Fact * aperture()=0
virtual CameraMode cameraMode() const
virtual void startZoom(int direction)=0
virtual int version() const =0
virtual bool toggleVideoRecording()=0
virtual QString storageFreeStr() const =0
void trackingImagePointChanged()
virtual ThermalViewMode thermalMode() const =0
void thermalOpacityChanged()
void currentStreamChanged()
void thermalModeChanged()
void streamLabelsChanged()
void thermalStreamChanged()
virtual ~MavlinkCameraControlInterface()
PhotoCaptureStatus _photoCaptureStatusValue
virtual bool photosInVideoMode() const =0
virtual CapturePhotosState capturePhotosState() const =0
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)=0
@ PHOTO_CAPTURE_TIMELAPSE
virtual bool hasVideoStream() const =0
@ CaptureVideoStateDisabled
@ CaptureVideoStateCapturing
virtual bool hasTracking() const =0
virtual void resetSettings()=0
QString captureVideoStatusToStr(uint8_t video_status)
void dataReady(const QByteArray &data)
void photoCaptureModeChanged()
virtual int photoLapseCount() const
QTimer _videoRecordTimeUpdateTimer
virtual void _paramDone()=0
Camera parameter handler.
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.