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