QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMSensorsComponentController.h
Go to the documentation of this file.
1#pragma once
2
4#include "QGCMAVLink.h"
5
6#include <QtCore/QLoggingCategory>
7#include <QtCore/QObject>
8#include <QtQuick/QQuickItem>
9#include <QtQmlIntegration/QtQmlIntegration>
10
11Q_DECLARE_LOGGING_CATEGORY(APMSensorsComponentControllerLog)
12Q_DECLARE_LOGGING_CATEGORY(APMSensorsComponentControllerVerboseLog)
13
15class LinkInterface;
16
19{
20 Q_OBJECT
21 QML_ELEMENT
22 Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
23 Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
24
25 Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton)
26 Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
27 Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText)
28
29 Q_PROPERTY(bool compassSetupNeeded READ compassSetupNeeded NOTIFY setupNeededChanged)
30 Q_PROPERTY(bool accelSetupNeeded READ accelSetupNeeded NOTIFY setupNeededChanged)
31
32 Q_PROPERTY(bool showOrientationCalArea MEMBER _showOrientationCalArea NOTIFY showOrientationCalAreaChanged)
33
34 Q_PROPERTY(bool orientationCalDownSideDone MEMBER _orientationCalDownSideDone NOTIFY orientationCalSidesDoneChanged)
35 Q_PROPERTY(bool orientationCalUpsideDownSideDone MEMBER _orientationCalUpsideDownSideDone NOTIFY orientationCalSidesDoneChanged)
36 Q_PROPERTY(bool orientationCalLeftSideDone MEMBER _orientationCalLeftSideDone NOTIFY orientationCalSidesDoneChanged)
37 Q_PROPERTY(bool orientationCalRightSideDone MEMBER _orientationCalRightSideDone NOTIFY orientationCalSidesDoneChanged)
38 Q_PROPERTY(bool orientationCalNoseDownSideDone MEMBER _orientationCalNoseDownSideDone NOTIFY orientationCalSidesDoneChanged)
39 Q_PROPERTY(bool orientationCalTailDownSideDone MEMBER _orientationCalTailDownSideDone NOTIFY orientationCalSidesDoneChanged)
40
41 Q_PROPERTY(bool orientationCalDownSideVisible MEMBER _orientationCalDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
42 Q_PROPERTY(bool orientationCalUpsideDownSideVisible MEMBER _orientationCalUpsideDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
43 Q_PROPERTY(bool orientationCalLeftSideVisible MEMBER _orientationCalLeftSideVisible NOTIFY orientationCalSidesVisibleChanged)
44 Q_PROPERTY(bool orientationCalRightSideVisible MEMBER _orientationCalRightSideVisible NOTIFY orientationCalSidesVisibleChanged)
45 Q_PROPERTY(bool orientationCalNoseDownSideVisible MEMBER _orientationCalNoseDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
46 Q_PROPERTY(bool orientationCalTailDownSideVisible MEMBER _orientationCalTailDownSideVisible NOTIFY orientationCalSidesVisibleChanged)
47
48 Q_PROPERTY(bool orientationCalDownSideInProgress MEMBER _orientationCalDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
49 Q_PROPERTY(bool orientationCalUpsideDownSideInProgress MEMBER _orientationCalUpsideDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
50 Q_PROPERTY(bool orientationCalLeftSideInProgress MEMBER _orientationCalLeftSideInProgress NOTIFY orientationCalSidesInProgressChanged)
51 Q_PROPERTY(bool orientationCalRightSideInProgress MEMBER _orientationCalRightSideInProgress NOTIFY orientationCalSidesInProgressChanged)
52 Q_PROPERTY(bool orientationCalNoseDownSideInProgress MEMBER _orientationCalNoseDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
53 Q_PROPERTY(bool orientationCalTailDownSideInProgress MEMBER _orientationCalTailDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
54
55 Q_PROPERTY(bool orientationCalDownSideRotate MEMBER _orientationCalDownSideRotate NOTIFY orientationCalSidesRotateChanged)
56 Q_PROPERTY(bool orientationCalUpsideDownSideRotate MEMBER _orientationCalUpsideDownSideRotate NOTIFY orientationCalSidesRotateChanged)
57 Q_PROPERTY(bool orientationCalLeftSideRotate MEMBER _orientationCalLeftSideRotate NOTIFY orientationCalSidesRotateChanged)
58 Q_PROPERTY(bool orientationCalRightSideRotate MEMBER _orientationCalRightSideRotate NOTIFY orientationCalSidesRotateChanged)
59 Q_PROPERTY(bool orientationCalNoseDownSideRotate MEMBER _orientationCalNoseDownSideRotate NOTIFY orientationCalSidesRotateChanged)
60 Q_PROPERTY(bool orientationCalTailDownSideRotate MEMBER _orientationCalTailDownSideRotate NOTIFY orientationCalSidesRotateChanged)
61
62 Q_PROPERTY(bool waitingForCancel MEMBER _waitingForCancel NOTIFY waitingForCancelChanged)
63
64 Q_PROPERTY(bool compass1CalSucceeded READ compass1CalSucceeded NOTIFY compass1CalSucceededChanged)
65 Q_PROPERTY(bool compass2CalSucceeded READ compass2CalSucceeded NOTIFY compass2CalSucceededChanged)
66 Q_PROPERTY(bool compass3CalSucceeded READ compass3CalSucceeded NOTIFY compass3CalSucceededChanged)
67
68 Q_PROPERTY(double compass1CalFitness READ compass1CalFitness NOTIFY compass1CalFitnessChanged)
69 Q_PROPERTY(double compass2CalFitness READ compass2CalFitness NOTIFY compass2CalFitnessChanged)
70 Q_PROPERTY(double compass3CalFitness READ compass3CalFitness NOTIFY compass3CalFitnessChanged)
71
72public:
73 explicit APMSensorsComponentController(QObject *parent = nullptr);
75
76 Q_INVOKABLE void calibrateCompass();
77 Q_INVOKABLE void calibrateAccel(bool doSimpleAccelCal);
78 Q_INVOKABLE void calibrateCompassNorth(float lat, float lon, int mask);
79 Q_INVOKABLE void calibrateGyro();
80 Q_INVOKABLE void calibrateMotorInterference();
81 Q_INVOKABLE void levelHorizon();
82 Q_INVOKABLE void calibratePressure();
83 Q_INVOKABLE void cancelCalibration();
84 Q_INVOKABLE void nextClicked();
85 Q_INVOKABLE bool usingUDPLink() const;
86
87 bool compassSetupNeeded() const;
88 bool accelSetupNeeded() const;
89
90 bool compass1CalSucceeded() const { return _rgCompassCalSucceeded[0]; }
91 bool compass2CalSucceeded() const { return _rgCompassCalSucceeded[1]; }
92 bool compass3CalSucceeded() const { return _rgCompassCalSucceeded[2]; }
93
94 double compass1CalFitness() const { return _rgCompassCalFitness[0]; }
95 double compass2CalFitness() const { return _rgCompassCalFitness[1]; }
96 double compass3CalFitness() const { return _rgCompassCalFitness[2]; }
97
98signals:
109 void compass1CalSucceededChanged(bool compass1CalSucceeded);
110 void compass2CalSucceededChanged(bool compass2CalSucceeded);
111 void compass3CalSucceededChanged(bool compass3CalSucceeded);
112 void compass1CalFitnessChanged(double compass1CalFitness);
113 void compass2CalFitnessChanged(double compass2CalFitness);
114 void compass3CalFitnessChanged(double compass3CalFitness);
115 void setAllCalButtonsEnabled(bool enabled);
116
117private slots:
118 void _handleTextMessage(int sysid, int componentid, int severity, const QString &text, const QString &description);
119 void _mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message);
120 void _mavCommandResult(int vehicleId, int component, int command, int result, int failureCode);
121
122private:
123 void _startLogCalibration();
124 void _startVisualCalibration();
126 void _appendStatusLog(const QString &text);
127 void _refreshParams();
128 void _hideAllCalAreas();
129 void _resetInternalState();
130 void _handleCommandAck(const mavlink_message_t &message);
131 void _handleMagCalProgress(const mavlink_message_t &message);
132 void _handleMagCalReport(const mavlink_message_t &message);
133 bool _handleCmdLongAccelcalVehiclePos(const mavlink_command_long_t &commandLong);
134 void _handleCommandLong(const mavlink_message_t &message);
135 void _restorePreviousCompassCalFitness();
136
137 enum StopCalibrationCode {
138 StopCalibrationSuccess,
139 StopCalibrationSuccessShowLog,
140 StopCalibrationFailed,
141 StopCalibrationCancelled
142 };
143 void _stopCalibration(StopCalibrationCode code);
144
145 void _updateAndEmitShowOrientationCalArea(bool show);
146
147 APMSensorsComponent *_sensorsComponent = nullptr;
148
149 QQuickItem *_statusLog = nullptr;
150 QQuickItem *_progressBar = nullptr;
151 QQuickItem *_nextButton = nullptr;
152 QQuickItem *_cancelButton = nullptr;
153 QQuickItem *_orientationCalAreaHelpText = nullptr;
154
155 bool _showOrientationCalArea = false;
156
158
159 uint8_t _rgCompassCalProgress[3];
160 bool _rgCompassCalComplete[3];
161 bool _rgCompassCalSucceeded[3];
162 float _rgCompassCalFitness[3];
163
164 bool _orientationCalDownSideDone = false;;
165 bool _orientationCalUpsideDownSideDone = false;;
166 bool _orientationCalLeftSideDone = false;;
167 bool _orientationCalRightSideDone = false;;
168 bool _orientationCalNoseDownSideDone = false;;
169 bool _orientationCalTailDownSideDone = false;;
170
171 bool _orientationCalDownSideVisible = false;;
172 bool _orientationCalUpsideDownSideVisible = false;;
173 bool _orientationCalLeftSideVisible = false;;
174 bool _orientationCalRightSideVisible = false;;
175 bool _orientationCalNoseDownSideVisible = false;;
176 bool _orientationCalTailDownSideVisible = false;;
177
178 bool _orientationCalDownSideInProgress = false;;
179 bool _orientationCalUpsideDownSideInProgress = false;;
180 bool _orientationCalLeftSideInProgress = false;;
181 bool _orientationCalRightSideInProgress = false;;
182 bool _orientationCalNoseDownSideInProgress = false;;
183 bool _orientationCalTailDownSideInProgress = false;;
184
185 bool _orientationCalDownSideRotate = false;;
186 bool _orientationCalUpsideDownSideRotate = false;;
187 bool _orientationCalLeftSideRotate = false;;
188 bool _orientationCalRightSideRotate = false;;
189 bool _orientationCalNoseDownSideRotate = false;;
190 bool _orientationCalTailDownSideRotate = false;;
191
192 bool _waitingForCancel = false;
193
194 bool _restoreCompassCalFitness = false;
195 float _previousCompassCalFitness = 0.;
196 static constexpr const char *_compassCalFitnessParam = "COMPASS_CAL_FIT";
197
198 static constexpr int _supportedFirmwareCalVersion = 2;
199};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
Sensors Component MVC Controller for SensorsComponent.qml.
void compass3CalFitnessChanged(double compass3CalFitness)
void compass1CalFitnessChanged(double compass1CalFitness)
void compass2CalFitnessChanged(double compass2CalFitness)
void compass2CalSucceededChanged(bool compass2CalSucceeded)
void setAllCalButtonsEnabled(bool enabled)
void compass3CalSucceededChanged(bool compass3CalSucceeded)
void compass1CalSucceededChanged(bool compass1CalSucceeded)
void calibrationComplete(QGCMAVLink::CalibrationType calType)
Used for handling missing Facts from C++ code.
The link interface defines the interface for all links used to communicate with the ground station ap...