|
|
@ -138,12 +138,21 @@ public: |
|
|
|
THERMAL_PIP, |
|
|
|
THERMAL_PIP, |
|
|
|
}; |
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
enum TrackingStatus { |
|
|
|
|
|
|
|
TRACKING_UNKNOWN = 0, |
|
|
|
|
|
|
|
TRACKING_SUPPORTED = 1, |
|
|
|
|
|
|
|
TRACKING_ENABLED = 2, |
|
|
|
|
|
|
|
TRACKING_RECTANGLE = 4, |
|
|
|
|
|
|
|
TRACKING_POINT = 8 |
|
|
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
Q_ENUM(CameraMode) |
|
|
|
Q_ENUM(CameraMode) |
|
|
|
Q_ENUM(VideoStatus) |
|
|
|
Q_ENUM(VideoStatus) |
|
|
|
Q_ENUM(PhotoStatus) |
|
|
|
Q_ENUM(PhotoStatus) |
|
|
|
Q_ENUM(PhotoMode) |
|
|
|
Q_ENUM(PhotoMode) |
|
|
|
Q_ENUM(StorageStatus) |
|
|
|
Q_ENUM(StorageStatus) |
|
|
|
Q_ENUM(ThermalViewMode) |
|
|
|
Q_ENUM(ThermalViewMode) |
|
|
|
|
|
|
|
Q_ENUM(TrackingStatus) |
|
|
|
|
|
|
|
|
|
|
|
Q_PROPERTY(int version READ version NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(int version READ version NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged) |
|
|
@ -158,6 +167,7 @@ public: |
|
|
|
Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged) |
|
|
|
|
|
|
|
Q_PROPERTY(bool hasTracking READ hasTracking NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged) |
|
|
|
Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged) |
|
|
@ -197,6 +207,10 @@ public: |
|
|
|
Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged) |
|
|
|
Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged) |
|
|
|
Q_PROPERTY(ThermalViewMode thermalMode READ thermalMode WRITE setThermalMode NOTIFY thermalModeChanged) |
|
|
|
Q_PROPERTY(ThermalViewMode thermalMode READ thermalMode WRITE setThermalMode NOTIFY thermalModeChanged) |
|
|
|
Q_PROPERTY(double thermalOpacity READ thermalOpacity WRITE setThermalOpacity NOTIFY thermalOpacityChanged) |
|
|
|
Q_PROPERTY(double thermalOpacity READ thermalOpacity WRITE setThermalOpacity NOTIFY thermalOpacityChanged) |
|
|
|
|
|
|
|
Q_PROPERTY(bool trackingEnabled READ trackingEnabled WRITE setTrackingEnabled NOTIFY trackingEnabledChanged) |
|
|
|
|
|
|
|
Q_PROPERTY(TrackingStatus trackingStatus READ trackingStatus CONSTANT) |
|
|
|
|
|
|
|
Q_PROPERTY(bool trackingImageStatus READ trackingImageStatus NOTIFY trackingImageStatusChanged) |
|
|
|
|
|
|
|
Q_PROPERTY(QRectF trackingImageRect READ trackingImageRect NOTIFY trackingImageStatusChanged) |
|
|
|
|
|
|
|
|
|
|
|
Q_INVOKABLE virtual void setVideoMode (); |
|
|
|
Q_INVOKABLE virtual void setVideoMode (); |
|
|
|
Q_INVOKABLE virtual void setPhotoMode (); |
|
|
|
Q_INVOKABLE virtual void setPhotoMode (); |
|
|
@ -213,6 +227,9 @@ public: |
|
|
|
Q_INVOKABLE virtual void stopZoom (); |
|
|
|
Q_INVOKABLE virtual void stopZoom (); |
|
|
|
Q_INVOKABLE virtual void stopStream (); |
|
|
|
Q_INVOKABLE virtual void stopStream (); |
|
|
|
Q_INVOKABLE virtual void resumeStream (); |
|
|
|
Q_INVOKABLE virtual void resumeStream (); |
|
|
|
|
|
|
|
Q_INVOKABLE virtual void startTracking (QRectF rec); |
|
|
|
|
|
|
|
Q_INVOKABLE virtual void startTracking (QPointF point, double radius); |
|
|
|
|
|
|
|
Q_INVOKABLE virtual void stopTracking (); |
|
|
|
|
|
|
|
|
|
|
|
virtual int version () { return _version; } |
|
|
|
virtual int version () { return _version; } |
|
|
|
virtual QString modelName () { return _modelName; } |
|
|
|
virtual QString modelName () { return _modelName; } |
|
|
@ -226,6 +243,7 @@ public: |
|
|
|
virtual bool hasModes () { return _info.flags & CAMERA_CAP_FLAGS_HAS_MODES; } |
|
|
|
virtual bool hasModes () { return _info.flags & CAMERA_CAP_FLAGS_HAS_MODES; } |
|
|
|
virtual bool hasZoom () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; } |
|
|
|
virtual bool hasZoom () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; } |
|
|
|
virtual bool hasFocus () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; } |
|
|
|
virtual bool hasFocus () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; } |
|
|
|
|
|
|
|
virtual bool hasTracking () { return _trackingStatus & TRACKING_SUPPORTED; } |
|
|
|
virtual bool hasVideoStream () { return _info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; } |
|
|
|
virtual bool hasVideoStream () { return _info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; } |
|
|
|
virtual bool photosInVideoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; } |
|
|
|
virtual bool photosInVideoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; } |
|
|
|
virtual bool videoInPhotoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; } |
|
|
|
virtual bool videoInPhotoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; } |
|
|
@ -287,9 +305,18 @@ public: |
|
|
|
virtual void handleParamValue (const mavlink_param_ext_value_t& value); |
|
|
|
virtual void handleParamValue (const mavlink_param_ext_value_t& value); |
|
|
|
virtual void handleStorageInfo (const mavlink_storage_information_t& st); |
|
|
|
virtual void handleStorageInfo (const mavlink_storage_information_t& st); |
|
|
|
virtual void handleBatteryStatus (const mavlink_battery_status_t& bs); |
|
|
|
virtual void handleBatteryStatus (const mavlink_battery_status_t& bs); |
|
|
|
|
|
|
|
virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t *tis); |
|
|
|
virtual void handleVideoInfo (const mavlink_video_stream_information_t *vi); |
|
|
|
virtual void handleVideoInfo (const mavlink_video_stream_information_t *vi); |
|
|
|
virtual void handleVideoStatus (const mavlink_video_stream_status_t *vs); |
|
|
|
virtual void handleVideoStatus (const mavlink_video_stream_status_t *vs); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
virtual bool trackingEnabled () { return _trackingStatus & TRACKING_ENABLED; } |
|
|
|
|
|
|
|
virtual void setTrackingEnabled (bool set); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
virtual TrackingStatus trackingStatus () { return _trackingStatus; } |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
virtual bool trackingImageStatus() { return _trackingImageStatus.tracking_status == 1; } |
|
|
|
|
|
|
|
virtual QRectF trackingImageRect() { return _trackingImageRect; } |
|
|
|
|
|
|
|
|
|
|
|
/// Notify controller a parameter has changed
|
|
|
|
/// Notify controller a parameter has changed
|
|
|
|
virtual void factChanged (Fact* pFact); |
|
|
|
virtual void factChanged (Fact* pFact); |
|
|
|
/// Allow controller to modify or invalidate incoming parameter
|
|
|
|
/// Allow controller to modify or invalidate incoming parameter
|
|
|
@ -328,6 +355,8 @@ signals: |
|
|
|
void autoStreamChanged (); |
|
|
|
void autoStreamChanged (); |
|
|
|
void recordTimeChanged (); |
|
|
|
void recordTimeChanged (); |
|
|
|
void streamLabelsChanged (); |
|
|
|
void streamLabelsChanged (); |
|
|
|
|
|
|
|
void trackingEnabledChanged (); |
|
|
|
|
|
|
|
void trackingImageStatusChanged (); |
|
|
|
void thermalModeChanged (); |
|
|
|
void thermalModeChanged (); |
|
|
|
void thermalOpacityChanged (); |
|
|
|
void thermalOpacityChanged (); |
|
|
|
void storageStatusChanged (); |
|
|
|
void storageStatusChanged (); |
|
|
@ -338,6 +367,7 @@ protected: |
|
|
|
virtual void _setCameraMode (CameraMode mode); |
|
|
|
virtual void _setCameraMode (CameraMode mode); |
|
|
|
virtual void _requestStreamInfo (uint8_t streamID); |
|
|
|
virtual void _requestStreamInfo (uint8_t streamID); |
|
|
|
virtual void _requestStreamStatus (uint8_t streamID); |
|
|
|
virtual void _requestStreamStatus (uint8_t streamID); |
|
|
|
|
|
|
|
virtual void _requestTrackingStatus (); |
|
|
|
virtual QGCVideoStreamInfo* _findStream (uint8_t streamID, bool report = true); |
|
|
|
virtual QGCVideoStreamInfo* _findStream (uint8_t streamID, bool report = true); |
|
|
|
virtual QGCVideoStreamInfo* _findStream (const QString name); |
|
|
|
virtual QGCVideoStreamInfo* _findStream (const QString name); |
|
|
|
|
|
|
|
|
|
|
@ -428,4 +458,10 @@ protected: |
|
|
|
QStringList _streamLabels; |
|
|
|
QStringList _streamLabels; |
|
|
|
ThermalViewMode _thermalMode = THERMAL_BLEND; |
|
|
|
ThermalViewMode _thermalMode = THERMAL_BLEND; |
|
|
|
double _thermalOpacity = 85.0; |
|
|
|
double _thermalOpacity = 85.0; |
|
|
|
|
|
|
|
TrackingStatus _trackingStatus = TRACKING_UNKNOWN; |
|
|
|
|
|
|
|
QRectF _trackingMarquee; |
|
|
|
|
|
|
|
QPointF _trackingPoint; |
|
|
|
|
|
|
|
double _trackingRadius = 0.0; |
|
|
|
|
|
|
|
mavlink_camera_tracking_image_status_t _trackingImageStatus; |
|
|
|
|
|
|
|
QRectF _trackingImageRect; |
|
|
|
}; |
|
|
|
}; |
|
|
|