QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MavlinkCameraControl.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QLoggingCategory>
4#include <QtCore/QObject>
5#include <QtCore/QPointF>
6#include <QtCore/QRectF>
7#include <QtCore/QSizeF>
8
9#include "FactGroup.h"
10#include "QGCVideoStreamInfo.h"
11#include "QmlObjectListModel.h"
12
13#include <QtQmlIntegration/QtQmlIntegration>
14
16class Vehicle;
17
18Q_DECLARE_LOGGING_CATEGORY(CameraControlLog)
19Q_DECLARE_LOGGING_CATEGORY(CameraControlVerboseLog)
20
21
23{
24 Q_OBJECT
25 QML_ELEMENT
26 QML_UNCREATABLE("")
27 Q_PROPERTY(Fact* exposureMode READ exposureMode NOTIFY parametersReady)
28 Q_PROPERTY(Fact* ev READ ev NOTIFY parametersReady)
29 Q_PROPERTY(Fact* iso READ iso NOTIFY parametersReady)
30 Q_PROPERTY(Fact* shutterSpeed READ shutterSpeed NOTIFY parametersReady)
31 Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady)
32 Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady)
33 Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady)
34
35 Q_PROPERTY(int version READ version NOTIFY infoChanged)
36 Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged)
37 Q_PROPERTY(QString vendor READ vendor NOTIFY infoChanged)
38 Q_PROPERTY(QString firmwareVersion READ firmwareVersion NOTIFY infoChanged)
39 Q_PROPERTY(qreal focalLength READ focalLength NOTIFY infoChanged)
40 Q_PROPERTY(QSizeF sensorSize READ sensorSize NOTIFY infoChanged)
41 Q_PROPERTY(QSize resolution READ resolution NOTIFY infoChanged)
42 Q_PROPERTY(bool hasModes READ hasModes NOTIFY infoChanged)
43 Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY infoChanged)
44 Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged)
45 Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged)
46 Q_PROPERTY(bool hasTracking READ hasTracking NOTIFY infoChanged)
47 Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged)
48 Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged)
49 Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged)
50
51
52 Q_PROPERTY(CameraMode cameraMode READ cameraMode WRITE setCameraMode NOTIFY cameraModeChanged)
53
54 Q_PROPERTY(quint32 storageFree READ storageFree NOTIFY storageFreeChanged)
55 Q_PROPERTY(QString storageFreeStr READ storageFreeStr NOTIFY storageFreeChanged)
56 Q_PROPERTY(quint32 storageTotal READ storageTotal NOTIFY storageTotalChanged)
57 Q_PROPERTY(int batteryRemaining READ batteryRemaining NOTIFY batteryRemainingChanged)
58 Q_PROPERTY(QString batteryRemainingStr READ batteryRemainingStr NOTIFY batteryRemainingChanged)
59 Q_PROPERTY(bool paramComplete READ paramComplete NOTIFY parametersReady)
60 Q_PROPERTY(qreal zoomLevel READ zoomLevel WRITE setZoomLevel NOTIFY zoomLevelChanged)
61 Q_PROPERTY(qreal focusLevel READ focusLevel WRITE setFocusLevel NOTIFY focusLevelChanged)
62 Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
63 Q_PROPERTY(StorageStatus storageStatus READ storageStatus NOTIFY storageStatusChanged)
64 Q_PROPERTY(qreal photoLapse READ photoLapse WRITE setPhotoLapse NOTIFY photoLapseChanged)
65 Q_PROPERTY(int photoLapseCount READ photoLapseCount WRITE setPhotoLapseCount NOTIFY photoLapseCountChanged)
66 Q_PROPERTY(PhotoCaptureMode photoCaptureMode READ photoCaptureMode WRITE setPhotoCaptureMode NOTIFY photoCaptureModeChanged)
67 Q_PROPERTY(int currentStream READ currentStream WRITE setCurrentStream NOTIFY currentStreamChanged)
68 Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged)
69 Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged)
70 Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged)
71 Q_PROPERTY(QGCVideoStreamInfo* thermalStreamInstance READ thermalStreamInstance NOTIFY thermalStreamChanged)
72 Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged)
73 Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged)
74 Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged)
75 Q_PROPERTY(ThermalViewMode thermalMode READ thermalMode WRITE setThermalMode NOTIFY thermalModeChanged)
76 Q_PROPERTY(double thermalOpacity READ thermalOpacity WRITE setThermalOpacity NOTIFY thermalOpacityChanged)
77 Q_PROPERTY(bool trackingEnabled READ trackingEnabled WRITE setTrackingEnabled NOTIFY trackingEnabledChanged)
78 Q_PROPERTY(TrackingStatus trackingStatus READ trackingStatus CONSTANT)
79 Q_PROPERTY(bool trackingImageStatus READ trackingImageStatus NOTIFY trackingImageStatusChanged)
80 Q_PROPERTY(QRectF trackingImageRect READ trackingImageRect NOTIFY trackingImageStatusChanged)
81
82 // 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.
83 // They are not necessarily directly related to the MAVLink camera capabilities.
84 Q_PROPERTY(bool capturesVideo READ capturesVideo NOTIFY infoChanged)
85 Q_PROPERTY(bool capturesPhotos READ capturesPhotos NOTIFY infoChanged)
86
87 // These are "virtual" states which take into account both the mavlink camera capabilities as well as the gstreamer ability to locally record video
88 // 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
89 // based on both the camera info as well as the video manager status.
90 Q_PROPERTY(CaptureVideoState captureVideoState READ captureVideoState NOTIFY captureVideoStateChanged)
91 Q_PROPERTY(CapturePhotosState capturePhotosState READ capturePhotosState NOTIFY capturePhotosStateChanged)
92
93 friend class QGCCameraParamIO;
94
95public:
96 explicit MavlinkCameraControl(Vehicle *vehicle, QObject *parent = nullptr);
97 virtual ~MavlinkCameraControl();
98
100 CAM_MODE_UNDEFINED = -1,
101 CAM_MODE_PHOTO = 0,
102 CAM_MODE_VIDEO = 1,
103 CAM_MODE_SURVEY = 2,
104 };
105 Q_ENUM(CameraMode)
106
108 PHOTO_CAPTURE_SINGLE = 0,
110 };
111 Q_ENUM(PhotoCaptureMode)
112
118 Q_ENUM(CaptureVideoState)
119
126 Q_ENUM(CapturePhotosState)
127
129 STORAGE_EMPTY = STORAGE_STATUS_EMPTY,
130 STORAGE_UNFORMATTED = STORAGE_STATUS_UNFORMATTED,
131 STORAGE_READY = STORAGE_STATUS_READY,
132 STORAGE_NOT_SUPPORTED = STORAGE_STATUS_NOT_SUPPORTED
133 };
134 Q_ENUM(StorageStatus)
135
142 Q_ENUM(ThermalViewMode)
143
145 TRACKING_UNKNOWN = 0,
146 TRACKING_SUPPORTED = 1,
147 TRACKING_ENABLED = 2,
148 TRACKING_RECTANGLE = 4,
149 TRACKING_POINT = 8
150 };
151 Q_ENUM(TrackingStatus)
152
153 Q_INVOKABLE virtual void setCameraModeVideo() = 0;
154 Q_INVOKABLE virtual void setCameraModePhoto() = 0;
155 Q_INVOKABLE virtual void toggleCameraMode() = 0;
156 Q_INVOKABLE virtual bool takePhoto() = 0;
157 Q_INVOKABLE virtual bool stopTakePhoto() = 0;
158 Q_INVOKABLE virtual bool startVideoRecording() = 0;
159 Q_INVOKABLE virtual bool stopVideoRecording() = 0;
160 Q_INVOKABLE virtual bool toggleVideoRecording() = 0;
161 Q_INVOKABLE virtual void resetSettings() = 0;
162 Q_INVOKABLE virtual void formatCard(int id = 1) = 0;
163 Q_INVOKABLE virtual void stepZoom(int direction) = 0;
164 Q_INVOKABLE virtual void startZoom(int direction) = 0;
165 Q_INVOKABLE virtual void stopZoom() = 0;
166 Q_INVOKABLE virtual void stopStream() = 0;
167 Q_INVOKABLE virtual void resumeStream() = 0;
168 Q_INVOKABLE virtual void startTracking(QRectF rec) = 0;
169 Q_INVOKABLE virtual void startTracking(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 hasVideoStream() const = 0;
186 virtual bool photosInVideoMode() const = 0;
187 virtual bool videoInPhotoMode() const = 0;
188 virtual CaptureVideoState captureVideoState() const = 0;
189 virtual CapturePhotosState capturePhotosState() const = 0;
190
191 virtual int compID() const = 0;
192 virtual bool isBasic() const = 0;
193 virtual PhotoCaptureMode photoCaptureMode() const { return _photoCaptureMode; }
194 virtual qreal photoLapse() const { return _photoLapse; }
195 virtual int photoLapseCount() const { return _photoLapseCount; }
196 virtual CameraMode cameraMode() const { return _cameraMode; }
197 virtual StorageStatus storageStatus() const = 0;
198 virtual QStringList activeSettings() const = 0;
199 virtual quint32 storageFree() const = 0;
200 virtual QString storageFreeStr() const = 0;
201 virtual quint32 storageTotal() const = 0;
202 virtual int batteryRemaining() const = 0;
203 virtual QString batteryRemainingStr() const = 0;
204 virtual bool paramComplete() const = 0;
205 virtual qreal zoomLevel() const = 0;
206 virtual qreal focusLevel() const = 0;
207
211 virtual int currentStream() const = 0;
212 virtual void setCurrentStream(int stream) = 0;
213 virtual bool autoStream() const = 0;
214 virtual quint32 recordTime() const = 0;
215 virtual QString recordTimeStr() const = 0;
216
217 virtual Fact *exposureMode() = 0;
218 virtual Fact *ev() = 0;
219 virtual Fact *iso() = 0;
220 virtual Fact *shutterSpeed() = 0;
221 virtual Fact *aperture() = 0;
222 virtual Fact *wb() = 0;
223 virtual Fact *mode() = 0;
224
225 virtual QStringList streamLabels() const = 0;
226
227 virtual ThermalViewMode thermalMode() const = 0;
228 virtual void setThermalMode(ThermalViewMode mode) = 0;
229 virtual double thermalOpacity() const = 0;
230 virtual void setThermalOpacity(double val) = 0;
231
232 virtual void setZoomLevel(qreal level) = 0;
233 virtual void setFocusLevel(qreal level) = 0;
234 virtual void setCameraMode(CameraMode cameraMode) = 0;
235 virtual void setPhotoCaptureMode(PhotoCaptureMode mode) = 0;
236 virtual void setPhotoLapse(qreal interval) = 0;
237 virtual void setPhotoLapseCount(int count) = 0;
238
239 virtual bool trackingEnabled() const = 0;
240 virtual void setTrackingEnabled(bool set) = 0;
241
242 virtual TrackingStatus trackingStatus() const = 0;
243
244 virtual bool trackingImageStatus() const = 0;
245 virtual QRectF trackingImageRect() const = 0;
246
247 virtual void factChanged(Fact *pFact) = 0;
248 virtual bool incomingParameter(Fact *pFact, QVariant &newValue) = 0;
249 virtual bool validateParameter(Fact *pFact, QVariant &newValue) = 0;
250
251 virtual void handleBatteryStatus(const mavlink_battery_status_t &bs) = 0;
252 virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus) = 0;
253 virtual void handleParamExtAck(const mavlink_param_ext_ack_t &paramExtAck) = 0;
254 virtual void handleParamExtValue(const mavlink_param_ext_value_t &paramExtValue) = 0;
255 virtual void handleCameraSettings(const mavlink_camera_settings_t &settings) = 0;
256 virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation) = 0;
257 virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus) = 0;
258 virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation) = 0;
259 virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus) = 0;
260
261 QString cameraModeToStr(CameraMode mode);
262 QString captureImageStatusToStr(uint8_t image_status);
263 QString captureVideoStatusToStr(uint8_t video_status);
264 QString storageStatusToStr(uint8_t status);
265
266signals:
278 void dataReady(const QByteArray &data);
295
296protected slots:
297 virtual void _paramDone() = 0;
298
299protected:
301 VIDEO_CAPTURE_STATUS_STOPPED = 0,
304 VIDEO_CAPTURE_STATUS_UNDEFINED = 255
305 };
306
315
316 VideoCaptureStatus _videoCaptureStatus() const { return _videoCaptureStatusValue; }
317 PhotoCaptureStatus _photoCaptureStatus() const { return _photoCaptureStatusValue; }
318
319 Vehicle *_vehicle = nullptr;
320 CameraMode _cameraMode = CAM_MODE_UNDEFINED;
321 VideoCaptureStatus _videoCaptureStatusValue = VIDEO_CAPTURE_STATUS_STOPPED;
322 PhotoCaptureStatus _photoCaptureStatusValue = PHOTO_CAPTURE_IDLE;
323 PhotoCaptureMode _photoCaptureMode = PHOTO_CAPTURE_SINGLE;
324 qreal _photoLapse = 1.0;
325 int _photoLapseCount = 0;
327};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
A Fact is used to hold a single value within the system.
Definition Fact.h:19
Abstract base class for all camera controls: real and simulated.
void photoCaptureModeChanged()
virtual QString storageFreeStr() const =0
virtual CameraMode cameraMode() const
virtual int currentStream() const =0
virtual QGCVideoStreamInfo * currentStreamInstance()=0
virtual qreal photoLapse() const
virtual void handleCameraSettings(const mavlink_camera_settings_t &settings)=0
virtual void _paramDone()=0
virtual QGCVideoStreamInfo * thermalStreamInstance()=0
virtual TrackingStatus trackingStatus() const =0
void photoCaptureStatusChanged()
virtual Fact * aperture()=0
virtual void setCameraMode(CameraMode cameraMode)=0
PhotoCaptureStatus _photoCaptureStatus() const
virtual void handleBatteryStatus(const mavlink_battery_status_t &bs)=0
void dataReady(const QByteArray &data)
void trackingImageStatusChanged()
virtual void factChanged(Fact *pFact)=0
Notify controller a parameter has changed.
virtual QRectF trackingImageRect() const =0
virtual QStringList streamLabels() const =0
Stream names to show the user (for selection)
virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus)=0
virtual void setThermalOpacity(double val)=0
virtual void setPhotoCaptureMode(PhotoCaptureMode mode)=0
virtual qreal focusLevel() const =0
virtual Fact * ev()=0
virtual quint32 recordTime() const =0
virtual void setZoomLevel(qreal level)=0
virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation)=0
virtual bool trackingEnabled() const =0
virtual qreal zoomLevel() const =0
virtual bool incomingParameter(Fact *pFact, QVariant &newValue)=0
Allow controller to modify or invalidate incoming parameter.
virtual QmlObjectListModel * streams()=0
virtual void handleParamExtAck(const mavlink_param_ext_ack_t &paramExtAck)=0
virtual bool trackingImageStatus() const =0
VideoCaptureStatus _videoCaptureStatus() const
virtual void setCurrentStream(int stream)=0
void videoCaptureStatusChanged()
virtual int batteryRemaining() const =0
virtual QString recordTimeStr() const =0
virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation)=0
virtual bool paramComplete() const =0
virtual quint32 storageFree() const =0
void capturePhotosStateChanged()
virtual QString batteryRemainingStr() const =0
virtual int photoLapseCount() const
virtual double thermalOpacity() const =0
void captureVideoStateChanged()
virtual void setTrackingEnabled(bool set)=0
virtual void handleParamExtValue(const mavlink_param_ext_value_t &paramExtValue)=0
virtual Fact * mode()=0
virtual bool validateParameter(Fact *pFact, QVariant &newValue)=0
Allow controller to modify or invalidate parameter change.
virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus)=0
virtual QStringList activeSettings() const =0
virtual quint32 storageTotal() const =0
virtual Fact * wb()=0
virtual void setFocusLevel(qreal level)=0
virtual bool autoStream() const =0
virtual void setPhotoLapse(qreal interval)=0
virtual void setPhotoLapseCount(int count)=0
virtual ThermalViewMode thermalMode() const =0
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)=0
virtual StorageStatus storageStatus() const =0
void batteryRemainingChanged()
virtual Fact * exposureMode()=0
virtual Fact * shutterSpeed()=0
virtual Fact * iso()=0
virtual void setThermalMode(ThermalViewMode mode)=0
Camera parameter handler.
Definition QGCCameraIO.h:17
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
int id READ id CONSTANT(AutoPilotPlugin *autopilotPlugin MEMBER _autopilotPlugin CONSTANT) 1(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged) 1(QGeoCoordinate homePosition READ homePosition NOTIFY homePositionChanged) 1(QGeoCoordinate armedPosition READ armedPosition NOTIFY armedPositionChanged) 1(bool armed READ armed WRITE setArmedShowError NOTIFY armedChanged) 1(bool autoDisarm READ autoDisarm NOTIFY autoDisarmChanged) 1(bool flightModeSetAvailable READ flightModeSetAvailable CONSTANT) 1(QStringList flightModes READ flightModes NOTIFY flightModesChanged) 1(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged) 1(TrajectoryPoints *trajectoryPoints MEMBER _trajectoryPoints CONSTANT) 1(QmlObjectListModel *cameraTriggerPoints READ cameraTriggerPoints CONSTANT) 1(float latitude READ latitude NOTIFY coordinateChanged) 1(float longitude READ longitude NOTIFY coordinateChanged) 1(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged) 1(bool px4Firmware READ px4Firmware NOTIFY firmwareTypeChanged) 1(bool apmFirmware READ apmFirmware NOTIFY firmwareTypeChanged) 1(bool soloFirmware READ soloFirmware WRITE setSoloFirmware NOTIFY soloFirmwareChanged) 1(bool genericFirmware READ genericFirmware CONSTANT) 1(uint messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged) 1(uint messagesSent READ messagesSent NOTIFY messagesSentChanged) 1(uint messagesLost READ messagesLost NOTIFY messagesLostChanged) 1(bool airship READ airship NOTIFY vehicleTypeChanged) 1(bool fixedWing READ fixedWing NOTIFY vehicleTypeChanged) 1(bool multiRotor READ multiRotor NOTIFY vehicleTypeChanged) 1(bool vtol READ vtol NOTIFY vehicleTypeChanged) 1(bool rover READ rover NOTIFY vehicleTypeChanged) 1(bool sub READ sub NOTIFY vehicleTypeChanged) 1(VehicleSupports *supports READ supports CONSTANT) 1(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged) 1(int motorCount READ motorCount CONSTANT) 1(bool coaxialMotors READ coaxialMotors CONSTANT) 1(bool xConfigMotors READ xConfigMotors CONSTANT) 1(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT) 1(QString brandImageIndoor READ brandImageIndoor NOTIFY firmwareTypeChanged) 1(QString brandImageOutdoor READ brandImageOutdoor NOTIFY firmwareTypeChanged) 1(int sensorsPresentBits READ sensorsPresentBits NOTIFY sensorsPresentBitsChanged) 1(int sensorsEnabledBits READ sensorsEnabledBits NOTIFY sensorsEnabledBitsChanged) 1(int sensorsHealthBits READ sensorsHealthBits NOTIFY sensorsHealthBitsChanged) 1(int sensorsUnhealthyBits READ sensorsUnhealthyBits NOTIFY sensorsUnhealthyBitsChanged) 1(QString missionFlightMode READ missionFlightMode CONSTANT) 1(QString pauseFlightMode READ pauseFlightMode CONSTANT) 1(QString rtlFlightMode READ rtlFlightMode CONSTANT) 1(QString smartRTLFlightMode READ smartRTLFlightMode CONSTANT) 1(QString landFlightMode READ landFlightMode CONSTANT) 1(QString takeControlFlightMode READ takeControlFlightMode CONSTANT) 1(QString followFlightMode READ followFlightMode CONSTANT) 1(QString motorDetectionFlightMode READ motorDetectionFlightMode CONSTANT) 1(QString stabilizedFlightMode READ stabilizedFlightMode CONSTANT) 1(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged) 1(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged) 1(QString vehicleImageOpaque READ vehicleImageOpaque CONSTANT) 1(QString vehicleImageOutline READ vehicleImageOutline CONSTANT) 1(int telemetryRRSSI READ telemetryRRSSI NOTIFY telemetryRRSSIChanged) 1(int telemetryLRSSI READ telemetryLRSSI NOTIFY telemetryLRSSIChanged) 1(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged) 1(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged) 1(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged) 1(int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged) 1(int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged) 1(QVariantList toolIndicators READ toolIndicators NOTIFY toolIndicatorsChanged) 1(bool initialPlanRequestComplete READ initialPlanRequestComplete NOTIFY initialPlanRequestCompleteChanged) 1(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged) 1(bool inFwdFlight READ inFwdFlight NOTIFY inFwdFlightChanged) 1(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged) 1(quint64 mavlinkSentCount READ mavlinkSentCount NOTIFY mavlinkStatusChanged) 1(quint64 mavlinkReceivedCount READ mavlinkReceivedCount NOTIFY mavlinkStatusChanged) 1(quint64 mavlinkLossCount READ mavlinkLossCount NOTIFY mavlinkStatusChanged) 1(float mavlinkLossPercent READ mavlinkLossPercent NOTIFY mavlinkStatusChanged) 1(GimbalController *gimbalController READ gimbalController CONSTANT) 1(bool hasGripper READ hasGripper NOTIFY hasGripperChanged) 1(bool isROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged) 1(CheckList checkListState READ checkListState WRITE setCheckListState NOTIFY checkListStateChanged) 1(bool readyToFlyAvailable READ readyToFlyAvailable NOTIFY readyToFlyAvailableChanged) 1(bool readyToFly READ readyToFly NOTIFY readyToFlyChanged) 1(QObject *sysStatusSensorInfo READ sysStatusSensorInfo CONSTANT) 1(bool allSensorsHealthy READ allSensorsHealthy NOTIFY allSensorsHealthyChanged) 1(bool requiresGpsFix READ requiresGpsFix NOTIFY requiresGpsFixChanged) 1(double loadProgress READ loadProgress NOTIFY loadProgressChanged) 1(bool initialConnectComplete READ isInitialConnectComplete NOTIFY initialConnectComplete) 1(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged) 1(QGCMapCircle *orbitMapCircle READ orbitMapCircle CONSTANT) 1(bool flying READ flying NOTIFY flyingChanged) 1(bool landing READ landing NOTIFY landingChanged) 1(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged) 1(QString gotoFlightMode READ gotoFlightMode CONSTANT) 1(bool haveMRSpeedLimits READ haveMRSpeedLimits NOTIFY haveMRSpeedLimChanged) 1(bool haveFWSpeedLimits READ haveFWSpeedLimits NOTIFY haveFWSpeedLimChanged) 1(ParameterManager *parameterManager READ parameterManager CONSTANT) 1(VehicleLinkManager *vehicleLinkManager READ vehicleLinkManager CONSTANT) 1(VehicleObjectAvoidance *objectAvoidance READ objectAvoidance CONSTANT) 1(Autotune *autotune READ autotune CONSTANT) 1(RemoteIDManager *remoteIDManager READ remoteIDManager CONSTANT) 1(FactGroup *vehicle READ vehicleFactGroup CONSTANT) 1(FactGroup *gps READ gpsFactGroup CONSTANT) 1(FactGroup *gps2 READ gps2FactGroup CONSTANT) 1(FactGroup *gpsAggregate READ gpsAggregateFactGroup CONSTANT) 1(FactGroup *wind READ windFactGroup CONSTANT) 1(FactGroup *vibration READ vibrationFactGroup CONSTANT) 1(FactGroup *temperature READ temperatureFactGroup CONSTANT) 1(FactGroup *clock READ clockFactGroup CONSTANT) 1(FactGroup *setpoint READ setpointFactGroup CONSTANT) 1(FactGroup *estimatorStatus READ estimatorStatusFactGroup CONSTANT) 1(FactGroup *terrain READ terrainFactGroup CONSTANT) 1(FactGroup *distanceSensors READ distanceSensorFactGroup CONSTANT) 1(FactGroup *localPosition READ localPositionFactGroup CONSTANT) 1(FactGroup *localPositionSetpoint READ localPositionSetpointFactGroup CONSTANT) 1(FactGroup *hygrometer READ hygrometerFactGroup CONSTANT) 1(FactGroup *generator READ generatorFactGroup CONSTANT) 1(FactGroup *efi READ efiFactGroup CONSTANT) 1(Actuators *actuators READ actuators CONSTANT) 1(HealthAndArmingCheckReport *healthAndArmingCheckReport READ healthAndArmingCheckReport CONSTANT) 1(QmlObjectListModel *batteries READ batteries CONSTANT) 1(QmlObjectListModel *escs READ escs CONSTANT) 1(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged) 1(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged) 1(int firmwarePatchVersion READ firmwarePatchVersion NOTIFY firmwareVersionChanged) 1(int firmwareVersionType READ firmwareVersionType NOTIFY firmwareVersionChanged) 1(QString firmwareVersionTypeString READ firmwareVersionTypeString NOTIFY firmwareVersionChanged) 1(int firmwareCustomMajorVersion READ firmwareCustomMajorVersion NOTIFY firmwareCustomVersionChanged) 1(int firmwareCustomMinorVersion READ firmwareCustomMinorVersion NOTIFY firmwareCustomVersionChanged) 1(int firmwareCustomPatchVersion READ firmwareCustomPatchVersion NOTIFY firmwareCustomVersionChanged) 1(QString gitHash READ gitHash NOTIFY gitHashChanged) 1(quint64 vehicleUID READ vehicleUID NOTIFY vehicleUIDChanged) 1(QString vehicleUIDStr READ vehicleUIDStr NOTIFY vehicleUIDChanged) 1(bool mavlinkSigning READ mavlinkSigning NOTIFY mavlinkSigningChanged) 1 void resetCounters()
< Combination of enabled and health