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 <QtCore/QLoggingCategory>
5#include <QtQmlIntegration/QtQmlIntegration>
6
8
9Q_DECLARE_LOGGING_CATEGORY(SensorsComponentControllerLog)
10
11
13{
14 Q_OBJECT
15 QML_ELEMENT
16public:
18
19 Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
20 Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
21
22 Q_PROPERTY(QQuickItem* compassButton MEMBER _compassButton)
23 Q_PROPERTY(QQuickItem* gyroButton MEMBER _gyroButton)
24 Q_PROPERTY(QQuickItem* accelButton MEMBER _accelButton)
25 Q_PROPERTY(QQuickItem* airspeedButton MEMBER _airspeedButton)
26 Q_PROPERTY(QQuickItem* levelButton MEMBER _levelButton)
27 Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
28 Q_PROPERTY(QQuickItem* setOrientationsButton MEMBER _setOrientationsButton)
29 Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText)
30
31 Q_PROPERTY(bool showOrientationCalArea MEMBER _showOrientationCalArea NOTIFY showOrientationCalAreaChanged)
32
33 Q_PROPERTY(bool orientationCalDownSideDone MEMBER _orientationCalDownSideDone NOTIFY orientationCalSidesDoneChanged)
34 Q_PROPERTY(bool orientationCalUpsideDownSideDone MEMBER _orientationCalUpsideDownSideDone NOTIFY orientationCalSidesDoneChanged)
35 Q_PROPERTY(bool orientationCalLeftSideDone MEMBER _orientationCalLeftSideDone NOTIFY orientationCalSidesDoneChanged)
36 Q_PROPERTY(bool orientationCalRightSideDone MEMBER _orientationCalRightSideDone NOTIFY orientationCalSidesDoneChanged)
37 Q_PROPERTY(bool orientationCalNoseDownSideDone MEMBER _orientationCalNoseDownSideDone NOTIFY orientationCalSidesDoneChanged)
38 Q_PROPERTY(bool orientationCalTailDownSideDone MEMBER _orientationCalTailDownSideDone NOTIFY orientationCalSidesDoneChanged)
39
40 Q_PROPERTY(bool orientationCalDownSideVisible MEMBER _orientationCalDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
41 Q_PROPERTY(bool orientationCalUpsideDownSideVisible MEMBER _orientationCalUpsideDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
42 Q_PROPERTY(bool orientationCalLeftSideVisible MEMBER _orientationCalLeftSideVisible NOTIFY orientationCalSidesVisibleChanged)
43 Q_PROPERTY(bool orientationCalRightSideVisible MEMBER _orientationCalRightSideVisible NOTIFY orientationCalSidesVisibleChanged)
44 Q_PROPERTY(bool orientationCalNoseDownSideVisible MEMBER _orientationCalNoseDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
45 Q_PROPERTY(bool orientationCalTailDownSideVisible MEMBER _orientationCalTailDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
46
47 Q_PROPERTY(bool orientationCalDownSideInProgress MEMBER _orientationCalDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
48 Q_PROPERTY(bool orientationCalUpsideDownSideInProgress MEMBER _orientationCalUpsideDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
49 Q_PROPERTY(bool orientationCalLeftSideInProgress MEMBER _orientationCalLeftSideInProgress NOTIFY orientationCalSidesInProgressChanged)
50 Q_PROPERTY(bool orientationCalRightSideInProgress MEMBER _orientationCalRightSideInProgress NOTIFY orientationCalSidesInProgressChanged)
51 Q_PROPERTY(bool orientationCalNoseDownSideInProgress MEMBER _orientationCalNoseDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
52 Q_PROPERTY(bool orientationCalTailDownSideInProgress MEMBER _orientationCalTailDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
53
54 Q_PROPERTY(bool orientationCalDownSideRotate MEMBER _orientationCalDownSideRotate NOTIFY orientationCalSidesRotateChanged)
55 Q_PROPERTY(bool orientationCalUpsideDownSideRotate MEMBER _orientationCalUpsideDownSideRotate NOTIFY orientationCalSidesRotateChanged)
56 Q_PROPERTY(bool orientationCalLeftSideRotate MEMBER _orientationCalLeftSideRotate NOTIFY orientationCalSidesRotateChanged)
57 Q_PROPERTY(bool orientationCalRightSideRotate MEMBER _orientationCalRightSideRotate NOTIFY orientationCalSidesRotateChanged)
58 Q_PROPERTY(bool orientationCalNoseDownSideRotate MEMBER _orientationCalNoseDownSideRotate NOTIFY orientationCalSidesRotateChanged)
59 Q_PROPERTY(bool orientationCalTailDownSideRotate MEMBER _orientationCalTailDownSideRotate NOTIFY orientationCalSidesRotateChanged)
60
61 Q_PROPERTY(bool waitingForCancel MEMBER _waitingForCancel NOTIFY waitingForCancelChanged)
62
63 Q_INVOKABLE void calibrateCompass(void);
64 Q_INVOKABLE void calibrateGyro(void);
65 Q_INVOKABLE void calibrateAccel(void);
66 Q_INVOKABLE void calibrateLevel(void);
67 Q_INVOKABLE void calibrateAirspeed(void);
68 Q_INVOKABLE void cancelCalibration(void);
69 Q_INVOKABLE bool usingUDPLink(void);
70 Q_INVOKABLE void resetFactoryParameters();
71
72signals:
81 void magCalComplete(void);
82
83private slots:
84 void _handleUASTextMessage(int uasId, int compId, int severity, QString text, const QString &description);
85 void _handleParametersReset(bool success);
86
87private:
88 void _startLogCalibration(void);
89 void _startVisualCalibration(void);
90 void _appendStatusLog(const QString& text);
91 void _refreshParams(void);
92 void _hideAllCalAreas(void);
93 void _resetInternalState(void);
94
95 enum StopCalibrationCode {
96 StopCalibrationSuccess,
97 StopCalibrationFailed,
98 StopCalibrationCancelled
99 };
100 void _stopCalibration(StopCalibrationCode code);
101
102 void _updateAndEmitShowOrientationCalArea(bool show);
103
104 QQuickItem* _statusLog;
105 QQuickItem* _progressBar;
106 QQuickItem* _compassButton;
107 QQuickItem* _gyroButton;
108 QQuickItem* _accelButton;
109 QQuickItem* _airspeedButton;
110 QQuickItem* _levelButton;
111 QQuickItem* _cancelButton;
112 QQuickItem* _setOrientationsButton;
113 QQuickItem* _orientationCalAreaHelpText;
114
115 bool _showGyroCalArea;
116 bool _showOrientationCalArea;
117
118 bool _gyroCalInProgress;
119 bool _magCalInProgress;
120 bool _accelCalInProgress;
121 bool _airspeedCalInProgress;
122 bool _levelCalInProgress;
123
124 bool _orientationCalDownSideDone;
125 bool _orientationCalUpsideDownSideDone;
126 bool _orientationCalLeftSideDone;
127 bool _orientationCalRightSideDone;
128 bool _orientationCalNoseDownSideDone;
129 bool _orientationCalTailDownSideDone;
130
131 bool _orientationCalDownSideVisible;
132 bool _orientationCalUpsideDownSideVisible;
133 bool _orientationCalLeftSideVisible;
134 bool _orientationCalRightSideVisible;
135 bool _orientationCalNoseDownSideVisible;
136 bool _orientationCalTailDownSideVisible;
137
138 bool _orientationCalDownSideInProgress;
139 bool _orientationCalUpsideDownSideInProgress;
140 bool _orientationCalLeftSideInProgress;
141 bool _orientationCalRightSideInProgress;
142 bool _orientationCalNoseDownSideInProgress;
143 bool _orientationCalTailDownSideInProgress;
144
145 bool _orientationCalDownSideRotate;
146 bool _orientationCalUpsideDownSideRotate;
147 bool _orientationCalLeftSideRotate;
148 bool _orientationCalRightSideRotate;
149 bool _orientationCalNoseDownSideRotate;
150 bool _orientationCalTailDownSideRotate;
151
152 bool _unknownFirmwareVersion;
153 bool _waitingForCancel;
154
155 static const int _supportedFirmwareCalVersion = 2;
156};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
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 showOrientationCalAreaChanged(void)