QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SensorsComponentController.cc
Go to the documentation of this file.
2#include "QGCApplication.h"
3#include "ParameterManager.h"
4#include "Vehicle.h"
6
7QGC_LOGGING_CATEGORY(SensorsComponentControllerLog, "AutoPilotPlugins.SensorsComponentController")
8
10 : _statusLog (nullptr)
11 , _progressBar (nullptr)
12 , _compassButton (nullptr)
13 , _gyroButton (nullptr)
14 , _accelButton (nullptr)
15 , _airspeedButton (nullptr)
16 , _levelButton (nullptr)
17 , _cancelButton (nullptr)
18 , _setOrientationsButton (nullptr)
19 , _showOrientationCalArea (false)
20 , _gyroCalInProgress (false)
21 , _magCalInProgress (false)
22 , _accelCalInProgress (false)
23 , _airspeedCalInProgress (false)
24 , _levelCalInProgress (false)
25 , _orientationCalDownSideDone (false)
26 , _orientationCalUpsideDownSideDone (false)
27 , _orientationCalLeftSideDone (false)
28 , _orientationCalRightSideDone (false)
29 , _orientationCalNoseDownSideDone (false)
30 , _orientationCalTailDownSideDone (false)
31 , _orientationCalDownSideVisible (false)
32 , _orientationCalUpsideDownSideVisible (false)
33 , _orientationCalLeftSideVisible (false)
34 , _orientationCalRightSideVisible (false)
35 , _orientationCalNoseDownSideVisible (false)
36 , _orientationCalTailDownSideVisible (false)
37 , _orientationCalDownSideInProgress (false)
38 , _orientationCalUpsideDownSideInProgress (false)
39 , _orientationCalLeftSideInProgress (false)
40 , _orientationCalRightSideInProgress (false)
41 , _orientationCalNoseDownSideInProgress (false)
42 , _orientationCalTailDownSideInProgress (false)
43 , _orientationCalDownSideRotate (false)
44 , _orientationCalUpsideDownSideRotate (false)
45 , _orientationCalLeftSideRotate (false)
46 , _orientationCalRightSideRotate (false)
47 , _orientationCalNoseDownSideRotate (false)
48 , _orientationCalTailDownSideRotate (false)
49 , _unknownFirmwareVersion (false)
50 , _waitingForCancel (false)
51{
52 connect(_vehicle, &Vehicle::sensorsParametersResetAck, this, &SensorsComponentController::_handleParametersReset);
53
54}
55
57{
59 if (sharedLink) {
60 return sharedLink->linkConfiguration()->type() == LinkConfiguration::TypeUdp;
61 } else {
62 return false;
63 }
64}
65
67void SensorsComponentController::_appendStatusLog(const QString& text)
68{
69 if (!_statusLog) {
70 qWarning() << "Internal error";
71 return;
72 }
73
74 QString varText = text;
75 QMetaObject::invokeMethod(_statusLog,
76 "append",
77 Q_ARG(QString, varText));
78}
79
80void SensorsComponentController::_startLogCalibration(void)
81{
82 _unknownFirmwareVersion = false;
83 _hideAllCalAreas();
84
85 connect(_vehicle, &Vehicle::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
86
87 _cancelButton->setEnabled(false);
88}
89
90void SensorsComponentController::_startVisualCalibration(void)
91{
92 _compassButton->setEnabled(false);
93 _gyroButton->setEnabled(false);
94 _accelButton->setEnabled(false);
95 _airspeedButton->setEnabled(false);
96 _levelButton->setEnabled(false);
97 _setOrientationsButton->setEnabled(false);
98 _cancelButton->setEnabled(true);
99
100 _resetInternalState();
101
102 _progressBar->setProperty("value", 0);
103}
104
105void SensorsComponentController::_resetInternalState(void)
106{
107 _orientationCalDownSideDone = true;
108 _orientationCalUpsideDownSideDone = true;
109 _orientationCalLeftSideDone = true;
110 _orientationCalRightSideDone = true;
111 _orientationCalTailDownSideDone = true;
112 _orientationCalNoseDownSideDone = true;
113 _orientationCalDownSideInProgress = false;
114 _orientationCalUpsideDownSideInProgress = false;
115 _orientationCalLeftSideInProgress = false;
116 _orientationCalRightSideInProgress = false;
117 _orientationCalNoseDownSideInProgress = false;
118 _orientationCalTailDownSideInProgress = false;
119 _orientationCalDownSideRotate = false;
120 _orientationCalUpsideDownSideRotate = false;
121 _orientationCalLeftSideRotate = false;
122 _orientationCalRightSideRotate = false;
123 _orientationCalNoseDownSideRotate = false;
124 _orientationCalTailDownSideRotate = false;
125
129}
130
131void SensorsComponentController::_stopCalibration(SensorsComponentController::StopCalibrationCode code)
132{
133 disconnect(_vehicle, &Vehicle::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage);
134
135 _compassButton->setEnabled(true);
136 _gyroButton->setEnabled(true);
137 _accelButton->setEnabled(true);
138 _airspeedButton->setEnabled(true);
139 _levelButton->setEnabled(true);
140 _setOrientationsButton->setEnabled(true);
141 _cancelButton->setEnabled(false);
142
143 if (code == StopCalibrationSuccess) {
144 _resetInternalState();
145
146 _progressBar->setProperty("value", 1);
147 } else {
148 _progressBar->setProperty("value", 0);
149 }
150
151 _waitingForCancel = false;
153
154 _refreshParams();
155
156 switch (code) {
157 case StopCalibrationSuccess:
158 _orientationCalAreaHelpText->setProperty("text", tr("Calibration complete"));
159 if (!_airspeedCalInProgress && !_levelCalInProgress) {
160 emit resetStatusTextArea();
161 }
162 if (_magCalInProgress) {
163 emit magCalComplete();
164 }
165 break;
166
167 case StopCalibrationCancelled:
168 emit resetStatusTextArea();
169 _hideAllCalAreas();
170 break;
171
172 default:
173 // Assume failed
174 _hideAllCalAreas();
175 qgcApp()->showAppMessage(tr("Calibration failed. Calibration log will be displayed."));
176 break;
177 }
178
179 _magCalInProgress = false;
180 _accelCalInProgress = false;
181 _gyroCalInProgress = false;
182 _airspeedCalInProgress = false;
183}
184
190
191void SensorsComponentController::calibrateCompass(void)
192{
193 _startLogCalibration();
195}
196
202
208
214
215void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text, const QString &description)
216{
217 Q_UNUSED(compId);
218 Q_UNUSED(severity);
219 Q_UNUSED(description);
220
221 if (uasId != _vehicle->id()) {
222 return;
223 }
224
225 // Needed for level horizon calibration
226 text.replace("&lt;", "<");
227 text.replace("&gt;", ">");
228
229 if (text.contains("progress <")) {
230 QString percent = text.split("<").last().split(">").first();
231 bool ok;
232 int p = percent.toInt(&ok);
233 if (ok) {
234 if (_progressBar) {
235 _progressBar->setProperty("value", (float)(p / 100.0));
236 } else {
237 qWarning() << "Internal error";
238 }
239 }
240 return;
241 }
242
243 _appendStatusLog(text);
244 qCDebug(SensorsComponentControllerLog) << text;
245
246 if (_unknownFirmwareVersion) {
247 // We don't know how to do visual cal with the version of firwmare
248 return;
249 }
250
251 // All calibration messages start with [cal]
252 QString calPrefix("[cal] ");
253 if (!text.startsWith(calPrefix)) {
254 return;
255 }
256 text = text.right(text.length() - calPrefix.length());
257
258 QString calStartPrefix("calibration started: ");
259 if (text.startsWith(calStartPrefix)) {
260 text = text.right(text.length() - calStartPrefix.length());
261
262 // Split version number and cal type
263 QStringList parts = text.split(" ");
264 if (parts.count() != 2 && parts[0].toInt() != _supportedFirmwareCalVersion) {
265 _unknownFirmwareVersion = true;
266 QString msg = tr("Unsupported calibration firmware version, using log");
267 _appendStatusLog(msg);
268 qDebug() << msg;
269 return;
270 }
271
272 _startVisualCalibration();
273
274 text = parts[1];
275 if (text == "accel" || text == "mag" || text == "gyro") {
276 // Reset all progress indication
277 _orientationCalDownSideDone = false;
278 _orientationCalUpsideDownSideDone = false;
279 _orientationCalLeftSideDone = false;
280 _orientationCalRightSideDone = false;
281 _orientationCalTailDownSideDone = false;
282 _orientationCalNoseDownSideDone = false;
283 _orientationCalDownSideInProgress = false;
284 _orientationCalUpsideDownSideInProgress = false;
285 _orientationCalLeftSideInProgress = false;
286 _orientationCalRightSideInProgress = false;
287 _orientationCalNoseDownSideInProgress = false;
288 _orientationCalTailDownSideInProgress = false;
289
290 // Reset all visibility
291 _orientationCalDownSideVisible = false;
292 _orientationCalUpsideDownSideVisible = false;
293 _orientationCalLeftSideVisible = false;
294 _orientationCalRightSideVisible = false;
295 _orientationCalTailDownSideVisible = false;
296 _orientationCalNoseDownSideVisible = false;
297
298 _orientationCalAreaHelpText->setProperty("text", tr("Place your vehicle into one of the Incomplete orientations shown below and hold it still"));
299
300 if (text == "accel") {
301 _accelCalInProgress = true;
302 _orientationCalDownSideVisible = true;
303 _orientationCalUpsideDownSideVisible = true;
304 _orientationCalLeftSideVisible = true;
305 _orientationCalRightSideVisible = true;
306 _orientationCalTailDownSideVisible = true;
307 _orientationCalNoseDownSideVisible = true;
308 } else if (text == "mag") {
309
310 // Work out what the autopilot is configured to
311 int sides = 0;
312
314 // Read the requested calibration directions off the system
315 sides = _vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, "CAL_MAG_SIDES")->rawValue().toFloat();
316 } else {
317 // There is no valid setting, default to all six sides
318 sides = (1 << 5) | (1 << 4) | (1 << 3) | (1 << 2) | (1 << 1) | (1 << 0);
319 }
320
321 _magCalInProgress = true;
322 _orientationCalTailDownSideVisible = ((sides & (1 << 0)) > 0);
323 _orientationCalNoseDownSideVisible = ((sides & (1 << 1)) > 0);
324 _orientationCalLeftSideVisible = ((sides & (1 << 2)) > 0);
325 _orientationCalRightSideVisible = ((sides & (1 << 3)) > 0);
326 _orientationCalUpsideDownSideVisible = ((sides & (1 << 4)) > 0);
327 _orientationCalDownSideVisible = ((sides & (1 << 5)) > 0);
328 } else if (text == "gyro") {
329 _gyroCalInProgress = true;
330 _orientationCalDownSideVisible = true;
331 } else {
332 qWarning() << "Unknown calibration message type" << text;
333 }
337 _updateAndEmitShowOrientationCalArea(true);
338 } else if (text == "airspeed") {
339 _airspeedCalInProgress = true;
340 } else if (text == "level") {
341 _levelCalInProgress = true;
342 }
343 return;
344 }
345
346 if (text.endsWith("orientation detected")) {
347 QString side = text.section(" ", 0, 0);
348 qCDebug(SensorsComponentControllerLog) << "Side started" << side;
349
350 if (side == "down") {
351 _orientationCalDownSideInProgress = true;
352 if (_magCalInProgress) {
353 _orientationCalDownSideRotate = true;
354 }
355 } else if (side == "up") {
356 _orientationCalUpsideDownSideInProgress = true;
357 if (_magCalInProgress) {
358 _orientationCalUpsideDownSideRotate = true;
359 }
360 } else if (side == "left") {
361 _orientationCalLeftSideInProgress = true;
362 if (_magCalInProgress) {
363 _orientationCalLeftSideRotate = true;
364 }
365 } else if (side == "right") {
366 _orientationCalRightSideInProgress = true;
367 if (_magCalInProgress) {
368 _orientationCalRightSideRotate = true;
369 }
370 } else if (side == "front") {
371 _orientationCalNoseDownSideInProgress = true;
372 if (_magCalInProgress) {
373 _orientationCalNoseDownSideRotate = true;
374 }
375 } else if (side == "back") {
376 _orientationCalTailDownSideInProgress = true;
377 if (_magCalInProgress) {
378 _orientationCalTailDownSideRotate = true;
379 }
380 }
381
382 if (_magCalInProgress) {
383 _orientationCalAreaHelpText->setProperty("text", tr("Rotate the vehicle continuously as shown in the diagram until marked as Completed"));
384 } else {
385 _orientationCalAreaHelpText->setProperty("text", tr("Hold still in the current orientation"));
386 }
387
390 return;
391 }
392
393 if (text.endsWith("side done, rotate to a different side")) {
394 QString side = text.section(" ", 0, 0);
395 qCDebug(SensorsComponentControllerLog) << "Side finished" << side;
396
397 if (side == "down") {
398 _orientationCalDownSideInProgress = false;
399 _orientationCalDownSideDone = true;
400 _orientationCalDownSideRotate = false;
401 } else if (side == "up") {
402 _orientationCalUpsideDownSideInProgress = false;
403 _orientationCalUpsideDownSideDone = true;
404 _orientationCalUpsideDownSideRotate = false;
405 } else if (side == "left") {
406 _orientationCalLeftSideInProgress = false;
407 _orientationCalLeftSideDone = true;
408 _orientationCalLeftSideRotate = false;
409 } else if (side == "right") {
410 _orientationCalRightSideInProgress = false;
411 _orientationCalRightSideDone = true;
412 _orientationCalRightSideRotate = false;
413 } else if (side == "front") {
414 _orientationCalNoseDownSideInProgress = false;
415 _orientationCalNoseDownSideDone = true;
416 _orientationCalNoseDownSideRotate = false;
417 } else if (side == "back") {
418 _orientationCalTailDownSideInProgress = false;
419 _orientationCalTailDownSideDone = true;
420 _orientationCalTailDownSideRotate = false;
421 }
422
423 _orientationCalAreaHelpText->setProperty("text", tr("Place you vehicle into one of the orientations shown below and hold it still"));
424
428 return;
429 }
430
431 if (text.endsWith("side already completed")) {
432 _orientationCalAreaHelpText->setProperty("text", tr("Orientation already completed, place you vehicle into one of the incomplete orientations shown below and hold it still"));
433 return;
434 }
435
436 QString calCompletePrefix("calibration done:");
437 if (text.startsWith(calCompletePrefix)) {
438 _stopCalibration(StopCalibrationSuccess);
439 return;
440 }
441
442 if (text.startsWith("calibration cancelled")) {
443 _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
444 return;
445 }
446
447 if (text.startsWith("calibration failed")) {
448 _stopCalibration(StopCalibrationFailed);
449 return;
450 }
451}
452
453void SensorsComponentController::_refreshParams(void)
454{
455 QStringList fastRefreshList;
456
457 // We ask for a refresh on these first so that the rotation combo show up as fast as possible
458 fastRefreshList << "CAL_MAG0_ID" << "CAL_MAG1_ID" << "CAL_MAG2_ID" << "CAL_MAG0_ROT" << "CAL_MAG1_ROT" << "CAL_MAG2_ROT";
459 for (const QString &paramName : std::as_const(fastRefreshList)) {
461 }
462
463 // Now ask for all to refresh
466}
467
468void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
469{
470 _showOrientationCalArea = show;
472}
473
474void SensorsComponentController::_hideAllCalAreas(void)
475{
476 _updateAndEmitShowOrientationCalArea(false);
477}
478
480{
481 // The firmware doesn't allow us to cancel calibration. The best we can do is wait
482 // for it to timeout.
483 _waitingForCancel = true;
485 _cancelButton->setEnabled(false);
486 _vehicle->stopCalibration(true /* showError */);
487}
488
489void SensorsComponentController::_handleParametersReset(bool success)
490{
491 if (success) {
492 qgcApp()->showAppMessage(tr("Reset successful"));
493
494 QTimer::singleShot(1000, this, [this]() {
495 _refreshParams();
496 });
497 }
498 else {
499 qgcApp()->showAppMessage(tr("Reset failed"));
500 }
501}
502
504{
505 auto compId = _vehicle->defaultComponentId();
506
507 _vehicle->sendMavCommand(compId,
508 MAV_CMD_PREFLIGHT_STORAGE,
509 true, // showError
510 3, // Reset factory parameters
511 -1); // Don't do anything with mission storage
512}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define qgcApp()
#define QGC_LOGGING_CATEGORY(name, categoryStr)
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
void refreshParametersPrefix(int componentId, const QString &namePrefix)
Request a refresh on all parameters that begin with the specified prefix.
static constexpr int defaultComponentId
void refreshParameter(int componentId, const QString &paramName)
Request a refresh on the specific parameter.
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)
WeakLinkInterfacePtr primaryLink() const
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2309
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
void sensorsParametersResetAck(bool success)
int id() const
Definition Vehicle.h:425
int defaultComponentId() const
Definition Vehicle.h:711
ParameterManager * parameterManager()
Definition Vehicle.h:578
void startCalibration(QGCMAVLink::CalibrationType calType)
Definition Vehicle.cc:3218
void stopCalibration(bool showError)
Definition Vehicle.cc:3298