22 Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
23 Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
25 Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton)
26 Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
27 Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText)
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;
87 bool compassSetupNeeded()
const;
88 bool accelSetupNeeded()
const;
90 bool compass1CalSucceeded()
const {
return _rgCompassCalSucceeded[0]; }
91 bool compass2CalSucceeded()
const {
return _rgCompassCalSucceeded[1]; }
92 bool compass3CalSucceeded()
const {
return _rgCompassCalSucceeded[2]; }
94 double compass1CalFitness()
const {
return _rgCompassCalFitness[0]; }
95 double compass2CalFitness()
const {
return _rgCompassCalFitness[1]; }
96 double compass3CalFitness()
const {
return _rgCompassCalFitness[2]; }
118 void _handleTextMessage(
int sysid,
int componentid,
int severity,
const QString &text,
const QString &description);
120 void _mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode);
123 void _startLogCalibration();
124 void _startVisualCalibration();
126 void _appendStatusLog(
const QString &text);
127 void _refreshParams();
128 void _hideAllCalAreas();
129 void _resetInternalState();
133 bool _handleCmdLongAccelcalVehiclePos(
const mavlink_command_long_t &commandLong);
135 void _restorePreviousCompassCalFitness();
137 enum StopCalibrationCode {
138 StopCalibrationSuccess,
139 StopCalibrationSuccessShowLog,
140 StopCalibrationFailed,
141 StopCalibrationCancelled
143 void _stopCalibration(StopCalibrationCode code);
145 void _updateAndEmitShowOrientationCalArea(
bool show);
149 QQuickItem *_statusLog =
nullptr;
150 QQuickItem *_progressBar =
nullptr;
151 QQuickItem *_nextButton =
nullptr;
152 QQuickItem *_cancelButton =
nullptr;
153 QQuickItem *_orientationCalAreaHelpText =
nullptr;
155 bool _showOrientationCalArea =
false;
159 uint8_t _rgCompassCalProgress[3];
160 bool _rgCompassCalComplete[3];
161 bool _rgCompassCalSucceeded[3];
162 float _rgCompassCalFitness[3];
164 bool _orientationCalDownSideDone =
false;;
165 bool _orientationCalUpsideDownSideDone =
false;;
166 bool _orientationCalLeftSideDone =
false;;
167 bool _orientationCalRightSideDone =
false;;
168 bool _orientationCalNoseDownSideDone =
false;;
169 bool _orientationCalTailDownSideDone =
false;;
171 bool _orientationCalDownSideVisible =
false;;
172 bool _orientationCalUpsideDownSideVisible =
false;;
173 bool _orientationCalLeftSideVisible =
false;;
174 bool _orientationCalRightSideVisible =
false;;
175 bool _orientationCalNoseDownSideVisible =
false;;
176 bool _orientationCalTailDownSideVisible =
false;;
178 bool _orientationCalDownSideInProgress =
false;;
179 bool _orientationCalUpsideDownSideInProgress =
false;;
180 bool _orientationCalLeftSideInProgress =
false;;
181 bool _orientationCalRightSideInProgress =
false;;
182 bool _orientationCalNoseDownSideInProgress =
false;;
183 bool _orientationCalTailDownSideInProgress =
false;;
185 bool _orientationCalDownSideRotate =
false;;
186 bool _orientationCalUpsideDownSideRotate =
false;;
187 bool _orientationCalLeftSideRotate =
false;;
188 bool _orientationCalRightSideRotate =
false;;
189 bool _orientationCalNoseDownSideRotate =
false;;
190 bool _orientationCalTailDownSideRotate =
false;;
192 bool _waitingForCancel =
false;
194 bool _restoreCompassCalFitness =
false;
195 float _previousCompassCalFitness = 0.;
196 static constexpr const char *_compassCalFitnessParam =
"COMPASS_CAL_FIT";
198 static constexpr int _supportedFirmwareCalVersion = 2;