QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SensorsComponentController.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtQuick/QQuickItem>
4#include <QtQmlIntegration/QtQmlIntegration>
5
7
11{
12 Q_OBJECT
13 QML_ELEMENT
14public:
16
17 Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
18 Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
19
20 Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText)
21
23
24 Q_PROPERTY(bool showOrientationCalArea MEMBER _showOrientationCalArea NOTIFY showOrientationCalAreaChanged)
25
26 Q_PROPERTY(bool orientationCalDownSideDone MEMBER _orientationCalDownSideDone NOTIFY orientationCalSidesDoneChanged)
27 Q_PROPERTY(bool orientationCalUpsideDownSideDone MEMBER _orientationCalUpsideDownSideDone NOTIFY orientationCalSidesDoneChanged)
28 Q_PROPERTY(bool orientationCalLeftSideDone MEMBER _orientationCalLeftSideDone NOTIFY orientationCalSidesDoneChanged)
29 Q_PROPERTY(bool orientationCalRightSideDone MEMBER _orientationCalRightSideDone NOTIFY orientationCalSidesDoneChanged)
30 Q_PROPERTY(bool orientationCalNoseDownSideDone MEMBER _orientationCalNoseDownSideDone NOTIFY orientationCalSidesDoneChanged)
31 Q_PROPERTY(bool orientationCalTailDownSideDone MEMBER _orientationCalTailDownSideDone NOTIFY orientationCalSidesDoneChanged)
32
33 Q_PROPERTY(bool orientationCalDownSideVisible MEMBER _orientationCalDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
34 Q_PROPERTY(bool orientationCalUpsideDownSideVisible MEMBER _orientationCalUpsideDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
35 Q_PROPERTY(bool orientationCalLeftSideVisible MEMBER _orientationCalLeftSideVisible NOTIFY orientationCalSidesVisibleChanged)
36 Q_PROPERTY(bool orientationCalRightSideVisible MEMBER _orientationCalRightSideVisible NOTIFY orientationCalSidesVisibleChanged)
37 Q_PROPERTY(bool orientationCalNoseDownSideVisible MEMBER _orientationCalNoseDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
38 Q_PROPERTY(bool orientationCalTailDownSideVisible MEMBER _orientationCalTailDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
39
40 Q_PROPERTY(bool orientationCalDownSideInProgress MEMBER _orientationCalDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
41 Q_PROPERTY(bool orientationCalUpsideDownSideInProgress MEMBER _orientationCalUpsideDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
42 Q_PROPERTY(bool orientationCalLeftSideInProgress MEMBER _orientationCalLeftSideInProgress NOTIFY orientationCalSidesInProgressChanged)
43 Q_PROPERTY(bool orientationCalRightSideInProgress MEMBER _orientationCalRightSideInProgress NOTIFY orientationCalSidesInProgressChanged)
44 Q_PROPERTY(bool orientationCalNoseDownSideInProgress MEMBER _orientationCalNoseDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
45 Q_PROPERTY(bool orientationCalTailDownSideInProgress MEMBER _orientationCalTailDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
46
47 Q_PROPERTY(bool orientationCalDownSideRotate MEMBER _orientationCalDownSideRotate NOTIFY orientationCalSidesRotateChanged)
48 Q_PROPERTY(bool orientationCalUpsideDownSideRotate MEMBER _orientationCalUpsideDownSideRotate NOTIFY orientationCalSidesRotateChanged)
49 Q_PROPERTY(bool orientationCalLeftSideRotate MEMBER _orientationCalLeftSideRotate NOTIFY orientationCalSidesRotateChanged)
50 Q_PROPERTY(bool orientationCalRightSideRotate MEMBER _orientationCalRightSideRotate NOTIFY orientationCalSidesRotateChanged)
51 Q_PROPERTY(bool orientationCalNoseDownSideRotate MEMBER _orientationCalNoseDownSideRotate NOTIFY orientationCalSidesRotateChanged)
52 Q_PROPERTY(bool orientationCalTailDownSideRotate MEMBER _orientationCalTailDownSideRotate NOTIFY orientationCalSidesRotateChanged)
53
54 Q_PROPERTY(bool waitingForCancel MEMBER _waitingForCancel NOTIFY waitingForCancelChanged)
55
56 Q_INVOKABLE void calibrateCompass(void);
57 Q_INVOKABLE void calibrateGyro(void);
58 Q_INVOKABLE void calibrateAccel(void);
59 Q_INVOKABLE void calibrateLevel(void);
60 Q_INVOKABLE void calibrateAirspeed(void);
61 Q_INVOKABLE void cancelCalibration(void);
62 Q_INVOKABLE bool usingUDPLink(void);
63 Q_INVOKABLE void resetFactoryParameters();
64
65 bool calibrationActive() const { return _magCalInProgress || _gyroCalInProgress || _accelCalInProgress || _airspeedCalInProgress || _levelCalInProgress; }
66
67signals:
76 void magCalComplete(void);
78
79private slots:
80 void _handleUASTextMessage(int uasId, int compId, int severity, QString text, const QString &description);
81 void _handleParametersReset(bool success);
82
83private:
84 void _startLogCalibration(void);
85 void _startVisualCalibration(void);
86 void _appendStatusLog(const QString& text);
87 void _refreshParams(void);
88 void _hideAllCalAreas(void);
89 void _resetInternalState(void);
90
91 enum StopCalibrationCode {
92 StopCalibrationSuccess,
93 StopCalibrationFailed,
94 StopCalibrationCancelled
95 };
96 void _stopCalibration(StopCalibrationCode code);
97
98 void _updateAndEmitShowOrientationCalArea(bool show);
99
100 QQuickItem* _statusLog;
101 QQuickItem* _progressBar;
102 QQuickItem* _orientationCalAreaHelpText;
103
104 bool _showGyroCalArea;
105 bool _showOrientationCalArea;
106
107 bool _gyroCalInProgress;
108 bool _magCalInProgress;
109 bool _accelCalInProgress;
110 bool _airspeedCalInProgress;
111 bool _levelCalInProgress;
112
113 bool _orientationCalDownSideDone;
114 bool _orientationCalUpsideDownSideDone;
115 bool _orientationCalLeftSideDone;
116 bool _orientationCalRightSideDone;
117 bool _orientationCalNoseDownSideDone;
118 bool _orientationCalTailDownSideDone;
119
120 bool _orientationCalDownSideVisible;
121 bool _orientationCalUpsideDownSideVisible;
122 bool _orientationCalLeftSideVisible;
123 bool _orientationCalRightSideVisible;
124 bool _orientationCalNoseDownSideVisible;
125 bool _orientationCalTailDownSideVisible;
126
127 bool _orientationCalDownSideInProgress;
128 bool _orientationCalUpsideDownSideInProgress;
129 bool _orientationCalLeftSideInProgress;
130 bool _orientationCalRightSideInProgress;
131 bool _orientationCalNoseDownSideInProgress;
132 bool _orientationCalTailDownSideInProgress;
133
134 bool _orientationCalDownSideRotate;
135 bool _orientationCalUpsideDownSideRotate;
136 bool _orientationCalLeftSideRotate;
137 bool _orientationCalRightSideRotate;
138 bool _orientationCalNoseDownSideRotate;
139 bool _orientationCalTailDownSideRotate;
140
141 bool _unknownFirmwareVersion;
142 bool _waitingForCancel;
143
144 static const int _supportedFirmwareCalVersion = 2;
145};
Used for handling missing Facts from C++ code.
Sensors Component MVC Controller for SensorsComponent.qml.
void orientationCalSidesVisibleChanged(void)
void waitingForCancelChanged(void)
void orientationCalSidesInProgressChanged(void)
void orientationCalSidesDoneChanged(void)
void orientationCalSidesRotateChanged(void)
void calibrationActiveChanged(void)
void showOrientationCalAreaChanged(void)