QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMSensorsComponentController.cc
Go to the documentation of this file.
4#include "MAVLinkLib.h"
5#include "MAVLinkProtocol.h"
6#include "ParameterManager.h"
7#include "AppMessages.h"
9#include "Vehicle.h"
10#include "VehicleLinkManager.h"
11
12#include <QtCore/QVariant>
13
14QGC_LOGGING_CATEGORY(APMSensorsComponentControllerLog, "AutoPilotPlugins.APMSensorsComponentController")
15QGC_LOGGING_CATEGORY(APMSensorsComponentControllerVerboseLog, "AutoPilotPlugins.APMSensorsComponentController:verbose")
16
18 : FactPanelController(parent)
19{
20 APMAutoPilotPlugin *const apmPlugin = qobject_cast<APMAutoPilotPlugin*>(_vehicle->autopilotPlugin());
21
22 // Find the sensors component
23 for (const QVariant &varVehicleComponent : apmPlugin->vehicleComponents()) {
24 _sensorsComponent = qobject_cast<APMSensorsComponent*>(varVehicleComponent.value<VehicleComponent*>());
25 if (_sensorsComponent) {
26 break;
27 }
28 }
29
30 if (_sensorsComponent) {
32 } else {
33 qCWarning(APMSensorsComponentControllerLog) << "Sensors component is missing";
34 }
35
36}
37
39{
40 _restorePreviousCompassCalFitness();
41}
42
43void APMSensorsComponentController::_appendStatusLog(const QString &text)
44{
45 Q_ASSERT(_statusLog);
46
47 const QString varText = text;
48 (void) QMetaObject::invokeMethod(_statusLog, "append", varText);
49}
50
51void APMSensorsComponentController::_startLogCalibration()
52{
53 _hideAllCalAreas();
54
55 (void) connect(_vehicle, &Vehicle::textMessageReceived, this, &APMSensorsComponentController::_handleTextMessage);
56
57 emit setAllCalButtonsEnabled(false);
58 if ((_calTypeInProgress == QGCMAVLink::CalibrationAccel) || (_calTypeInProgress == QGCMAVLink::CalibrationAPMCompassMot)) {
59 _nextButton->setEnabled(true);
60 }
61 _cancelButton->setEnabled(_calTypeInProgress == QGCMAVLink::CalibrationMag);
62
63 (void) connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
64}
65
66void APMSensorsComponentController::_startVisualCalibration()
67{
68 emit setAllCalButtonsEnabled(false);
69 _cancelButton->setEnabled(true);
70 _nextButton->setEnabled(false);
71
72 _resetInternalState();
73
74 (void) _progressBar->setProperty("value", 0);
75
76 (void) connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
77}
78
79void APMSensorsComponentController::_resetInternalState()
80{
81 _orientationCalDownSideDone = true;
82 _orientationCalUpsideDownSideDone = true;
83 _orientationCalLeftSideDone = true;
84 _orientationCalRightSideDone = true;
85 _orientationCalTailDownSideDone = true;
86 _orientationCalNoseDownSideDone = true;
87 _orientationCalDownSideInProgress = false;
88 _orientationCalUpsideDownSideInProgress = false;
89 _orientationCalLeftSideInProgress = false;
90 _orientationCalRightSideInProgress = false;
91 _orientationCalNoseDownSideInProgress = false;
92 _orientationCalTailDownSideInProgress = false;
93 _orientationCalDownSideRotate = false;
94 _orientationCalUpsideDownSideRotate = false;
95 _orientationCalLeftSideRotate = false;
96 _orientationCalRightSideRotate = false;
97 _orientationCalNoseDownSideRotate = false;
98 _orientationCalTailDownSideRotate = false;
99
103}
104
105void APMSensorsComponentController::_stopCalibration(APMSensorsComponentController::StopCalibrationCode code)
106{
107 (void) disconnect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
109
110 (void) disconnect(_vehicle, &Vehicle::textMessageReceived, this, &APMSensorsComponentController::_handleTextMessage);
111
112 emit setAllCalButtonsEnabled(true);
113 _nextButton->setEnabled(false);
114 _cancelButton->setEnabled(false);
115
116 if (_calTypeInProgress == QGCMAVLink::CalibrationMag) {
117 _restorePreviousCompassCalFitness();
118 }
119
120 if (code == StopCalibrationSuccess) {
121 _resetInternalState();
122 (void) _progressBar->setProperty("value", 1);
123 if (parameterExists(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_LEARN"))) {
124 getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_LEARN"))->setRawValue(0);
125 }
126 } else {
127 (void) _progressBar->setProperty("value", 0);
128 }
129
130 _waitingForCancel = false;
132
133 _refreshParams();
134
135 switch (code) {
136 case StopCalibrationSuccess:
137 (void) _orientationCalAreaHelpText->setProperty("text", tr("Calibration complete"));
138 emit resetStatusTextArea();
139 emit calibrationComplete(_calTypeInProgress);
140 break;
141 case StopCalibrationSuccessShowLog:
142 emit calibrationComplete(_calTypeInProgress);
143 break;
144 case StopCalibrationCancelled:
145 emit resetStatusTextArea();
146 _hideAllCalAreas();
147 break;
148 default:
149 // Assume failed
150 _hideAllCalAreas();
151 QGC::showAppMessage(tr("Calibration failed. Calibration log will be displayed."));
152 break;
153 }
154
155 _calTypeInProgress = QGCMAVLink::CalibrationNone;
156}
157
158void APMSensorsComponentController::_mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
159{
160 Q_UNUSED(component); Q_UNUSED(failureCode);
161
162 if (_vehicle->id() != vehicleId) {
163 return;
164 }
165
166 switch (command) {
167 case MAV_CMD_DO_CANCEL_MAG_CAL:
168 (void) disconnect(_vehicle, &Vehicle::mavCommandResult, this, &APMSensorsComponentController::_mavCommandResult);
169 if (result == MAV_RESULT_ACCEPTED) {
170 // Onboard mag cal is supported
171 _calTypeInProgress = QGCMAVLink::CalibrationMag;
172 _rgCompassCalProgress[0] = 0;
173 _rgCompassCalProgress[1] = 0;
174 _rgCompassCalProgress[2] = 0;
175 _rgCompassCalComplete[0] = false;
176 _rgCompassCalComplete[1] = false;
177 _rgCompassCalComplete[2] = false;
178
179 _startLogCalibration();
180 uint8_t compassBits = 0;
181 if ((getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_DEV_ID"))->rawValue().toInt() > 0) &&
182 getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_USE"))->rawValue().toBool()) {
183 compassBits |= 1 << 0;
184 qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 1";
185 } else {
186 _rgCompassCalComplete[0] = true;
187 _rgCompassCalSucceeded[0] = true;
188 _rgCompassCalFitness[0] = 0;
189 }
190 if ((getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_DEV_ID2"))->rawValue().toInt() > 0) &&
191 getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_USE2"))->rawValue().toBool()) {
192 compassBits |= 1 << 1;
193 qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 2";
194 } else {
195 _rgCompassCalComplete[1] = true;
196 _rgCompassCalSucceeded[1] = true;
197 _rgCompassCalFitness[1] = 0;
198 }
199 if ((getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_DEV_ID3"))->rawValue().toInt() > 0) &&
200 getParameterFact(ParameterManager::defaultComponentId, QStringLiteral("COMPASS_USE3"))->rawValue().toBool()) {
201 compassBits |= 1 << 2;
202 qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 3";
203 } else {
204 _rgCompassCalComplete[2] = true;
205 _rgCompassCalSucceeded[2] = true;
206 _rgCompassCalFitness[2] = 0;
207 }
208
209 // We bump up the fitness value so calibration will always succeed
210 const Fact *const compassCalFitness = getParameterFact(ParameterManager::defaultComponentId, _compassCalFitnessParam);
211 _restoreCompassCalFitness = true;
212 _previousCompassCalFitness = compassCalFitness->rawValue().toFloat();
213 getParameterFact(ParameterManager::defaultComponentId, _compassCalFitnessParam)->setRawValue(100.0);
214
215 _appendStatusLog(tr("Rotate the vehicle randomly around all axes until the progress bar fills all the way to the right ."));
218 MAV_CMD_DO_START_MAG_CAL,
219 true, // showError
220 compassBits, // which compass(es) to calibrate
221 0, // no retry on failure
222 1, // save values after complete
223 0, // no delayed start
224 0 // no auto-reboot
225 );
226
227 }
228 break;
229 case MAV_CMD_DO_START_MAG_CAL:
230 if (result != MAV_RESULT_ACCEPTED) {
231 _restorePreviousCompassCalFitness();
232 }
233 break;
234 case MAV_CMD_FIXED_MAG_CAL_YAW:
235 if (result == MAV_RESULT_ACCEPTED) {
236 _appendStatusLog(tr("Successfully completed"));
237 _stopCalibration(StopCalibrationSuccessShowLog);
238 } else {
239 _appendStatusLog(tr("Failed"));
240 _stopCalibration(StopCalibrationFailed);
241 }
242 break;
243 default:
244 break;
245 }
246}
247
249{
250 // First we need to determine if the vehicle support onboard compass cal. There isn't an easy way to
251 // do this. A hack is to send the mag cancel command and see if it is accepted.
252 (void) connect(_vehicle, &Vehicle::mavCommandResult, this, &APMSensorsComponentController::_mavCommandResult);
253 _vehicle->sendMavCommand(_vehicle->defaultComponentId(), MAV_CMD_DO_CANCEL_MAG_CAL, false /* showError */);
254
255 // Now we wait for the result to come back
256}
257
259{
260 _startLogCalibration();
261 (void) connect(_vehicle, &Vehicle::mavCommandResult, this, &APMSensorsComponentController::_mavCommandResult);
262 _vehicle->sendMavCommand(_vehicle->defaultComponentId(), MAV_CMD_FIXED_MAG_CAL_YAW, true /* showError */, 0 /* north*/, mask, lat, lon);
263}
264
266{
267 _calTypeInProgress = QGCMAVLink::CalibrationAccel;
268 if (doSimpleAccelCal) {
269 _startLogCalibration();
270 _calTypeInProgress = QGCMAVLink::CalibrationAPMAccelSimple;
271 _vehicle->startCalibration(_calTypeInProgress);
272 return;
273 }
275 _startVisualCalibration();
276 _cancelButton->setEnabled(false);
277 (void) _orientationCalAreaHelpText->setProperty("text", tr("Hold still in the current orientation and press Next when ready"));
278
279 // Reset all progress indication
280 _orientationCalDownSideDone = false;
281 _orientationCalUpsideDownSideDone = false;
282 _orientationCalLeftSideDone = false;
283 _orientationCalRightSideDone = false;
284 _orientationCalTailDownSideDone = false;
285 _orientationCalNoseDownSideDone = false;
286 _orientationCalDownSideInProgress = false;
287 _orientationCalUpsideDownSideInProgress = false;
288 _orientationCalLeftSideInProgress = false;
289 _orientationCalRightSideInProgress = false;
290 _orientationCalNoseDownSideInProgress = false;
291 _orientationCalTailDownSideInProgress = false;
292
293 // Reset all visibility
294 _orientationCalDownSideVisible = false;
295 _orientationCalUpsideDownSideVisible = false;
296 _orientationCalLeftSideVisible = false;
297 _orientationCalRightSideVisible = false;
298 _orientationCalTailDownSideVisible = false;
299 _orientationCalNoseDownSideVisible = false;
300
301 _calTypeInProgress = QGCMAVLink::CalibrationAccel;
302 _orientationCalDownSideVisible = true;
303 _orientationCalUpsideDownSideVisible = true;
304 _orientationCalLeftSideVisible = true;
305 _orientationCalRightSideVisible = true;
306 _orientationCalTailDownSideVisible = true;
307 _orientationCalNoseDownSideVisible = true;
308
312 _updateAndEmitShowOrientationCalArea(true);
313
314 _vehicle->startCalibration(_calTypeInProgress);
315}
316
318{
319 _calTypeInProgress = QGCMAVLink::CalibrationAPMCompassMot;
321 _startLogCalibration();
322 _appendStatusLog(tr("Raise the throttle slowly to between 50% ~ 75% (the props will spin!) for 5 ~ 10 seconds."));
323 _appendStatusLog(tr("Quickly bring the throttle back down to zero"));
324 _appendStatusLog(tr("Press the Next button to complete the calibration"));
325 _vehicle->startCalibration(_calTypeInProgress);
326}
327
329{
330 _calTypeInProgress = QGCMAVLink::CalibrationLevel;
332 _startLogCalibration();
333 _appendStatusLog(tr("Hold the vehicle in its level flight position."));
334 _vehicle->startCalibration(_calTypeInProgress);
335}
336
338{
341 _startLogCalibration();
342 _appendStatusLog(tr("Requesting pressure calibration..."));
343 _vehicle->startCalibration(_calTypeInProgress);
344}
345
347{
348 _calTypeInProgress = QGCMAVLink::CalibrationGyro;
350 _startLogCalibration();
351 _appendStatusLog(tr("Requesting gyro calibration..."));
352 _vehicle->startCalibration(_calTypeInProgress);
353}
354
355void APMSensorsComponentController::_handleTextMessage(int sysid, int componentid, int severity, const QString &text, const QString &description)
356{
357 Q_UNUSED(componentid); Q_UNUSED(severity); Q_UNUSED(description);
358
359 if (sysid != _vehicle->id()) {
360 return;
361 }
362
363 const QString originalMessageText = text;
364 const QString messageText = text.toLower();
365
366 const QStringList hidePrefixList = { QStringLiteral("prearm:"), QStringLiteral("ekf"), QStringLiteral("arm"), QStringLiteral("initialising") };
367 for (const QString &hidePrefix : hidePrefixList) {
368 if (messageText.startsWith(hidePrefix)) {
369 return;
370 }
371 }
372
373 _appendStatusLog(originalMessageText);
374 qCDebug(APMSensorsComponentControllerLog) << originalMessageText << severity;
375}
376
377void APMSensorsComponentController::_refreshParams()
378{
379 static const QStringList fastRefreshList = {
380 QStringLiteral("COMPASS_OFS_X"), QStringLiteral("COMPASS_OFS_Y"), QStringLiteral("COMPASS_OFS_Z"),
381 QStringLiteral("INS_ACCOFFS_X"), QStringLiteral("INS_ACCOFFS_Y"), QStringLiteral("INS_ACCOFFS_Z")
382 };
383
384 for (const QString &paramName : fastRefreshList) {
386 }
387
388 // Now ask for all to refresh
391}
392
393void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
394{
395 _showOrientationCalArea = show;
397}
398
399void APMSensorsComponentController::_hideAllCalAreas()
400{
401 _updateAndEmitShowOrientationCalArea(false);
402}
403
405{
406 _cancelButton->setEnabled(false);
407
408 if (_calTypeInProgress == QGCMAVLink::CalibrationMag) {
409 _vehicle->sendMavCommand(_vehicle->defaultComponentId(), MAV_CMD_DO_CANCEL_MAG_CAL, true /* showError */);
410 _stopCalibration(StopCalibrationCancelled);
411 } else {
412 _waitingForCancel = true;
414 // The firmware doesn't always allow us to cancel calibration. The best we can do is wait
415 // for it to timeout.
416 _vehicle->stopCalibration(true /* showError */);
417 }
418}
419
421{
423 if (sharedLink) {
424 mavlink_message_t msg{};
425
426 (void) mavlink_msg_command_ack_pack_chan(
429 sharedLink->mavlinkChannel(),
430 &msg,
431 0, // command
432 1, // result
433 0, // progress
434 0, // result_param2
435 0, // target_system
436 0 // target_component
437 );
438
439 (void) _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
440
441 if (_calTypeInProgress == QGCMAVLink::CalibrationAPMCompassMot) {
442 _stopCalibration(StopCalibrationSuccess);
443 }
444 }
445}
446
448{
449 return _sensorsComponent->compassSetupNeeded();
450}
451
453{
454 return _sensorsComponent->accelSetupNeeded();
455}
456
458{
459 const SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
460 if (!sharedLink) {
461 return false;
462 }
463
464 return (sharedLink->linkConfiguration()->type() == LinkConfiguration::TypeUdp);
465}
466
467void APMSensorsComponentController::_handleCommandAck(const mavlink_message_t &message)
468{
469 if ((_calTypeInProgress == QGCMAVLink::CalibrationLevel) || (_calTypeInProgress == QGCMAVLink::CalibrationGyro) || (_calTypeInProgress == QGCMAVLink::CalibrationAPMPressureAirspeed) || (_calTypeInProgress == QGCMAVLink::CalibrationAPMAccelSimple)) {
470 mavlink_command_ack_t commandAck{};
471 mavlink_msg_command_ack_decode(&message, &commandAck);
472
473 if (commandAck.command == MAV_CMD_PREFLIGHT_CALIBRATION) {
474 switch (commandAck.result) {
475 case MAV_RESULT_IN_PROGRESS:
476 _appendStatusLog(tr("In progress"));
477 break;
478 case MAV_RESULT_ACCEPTED:
479 _appendStatusLog(tr("Successfully completed"));
480 _stopCalibration(StopCalibrationSuccessShowLog);
481 break;
482 default:
483 _appendStatusLog(tr("Failed"));
484 _stopCalibration(StopCalibrationFailed);
485 break;
486 }
487 }
488 }
489}
490
491void APMSensorsComponentController::_handleMagCalProgress(const mavlink_message_t &message)
492{
493 if (_calTypeInProgress != QGCMAVLink::CalibrationMag) {
494 return;
495 }
496
497 mavlink_mag_cal_progress_t magCalProgress{};
498 mavlink_msg_mag_cal_progress_decode(&message, &magCalProgress);
499
500 qCDebug(APMSensorsComponentControllerVerboseLog) << "id:mask:pct"
501 << magCalProgress.compass_id
502 << magCalProgress.cal_mask
503 << magCalProgress.completion_pct;
504
505 // How many compasses are we calibrating?
506 int compassCalCount = 0;
507 for (int i = 0; i < 3; i++) {
508 if (magCalProgress.cal_mask & (1 << i)) {
509 compassCalCount++;
510 }
511 }
512
513 if ((magCalProgress.compass_id < 3) && (compassCalCount != 0)) {
514 // Each compass gets a portion of the overall progress
515 _rgCompassCalProgress[magCalProgress.compass_id] = magCalProgress.completion_pct / compassCalCount;
516 }
517
518 if (_progressBar) {
519 (void) _progressBar->setProperty("value", static_cast<float>(_rgCompassCalProgress[0] + _rgCompassCalProgress[1] + _rgCompassCalProgress[2]) / 100.0);
520 }
521}
522
523void APMSensorsComponentController::_handleMagCalReport(const mavlink_message_t &message)
524{
525 if (_calTypeInProgress != QGCMAVLink::CalibrationMag) {
526 return;
527 }
528
529 mavlink_mag_cal_report_t magCalReport{};
530 mavlink_msg_mag_cal_report_decode(&message, &magCalReport);
531
532 qCDebug(APMSensorsComponentControllerVerboseLog) << "id:mask:status:fitness"
533 << magCalReport.compass_id << magCalReport.cal_mask << magCalReport.cal_status << magCalReport.fitness;
534
535 bool additionalCompassCompleted = false;
536 if ((magCalReport.compass_id < 3) && !_rgCompassCalComplete[magCalReport.compass_id]) {
537 if (magCalReport.cal_status == MAG_CAL_SUCCESS) {
538 _appendStatusLog(tr("Compass %1 calibration complete").arg(magCalReport.compass_id));
539 } else {
540 _appendStatusLog(tr("Compass %1 calibration below quality threshold").arg(magCalReport.compass_id));
541 }
542 _rgCompassCalComplete[magCalReport.compass_id] = true;
543 _rgCompassCalSucceeded[magCalReport.compass_id] = (magCalReport.cal_status == MAG_CAL_SUCCESS);
544 _rgCompassCalFitness[magCalReport.compass_id] = magCalReport.fitness;
545 additionalCompassCompleted = true;
546 }
547
548 if (_rgCompassCalComplete[0] && _rgCompassCalComplete[1] &&_rgCompassCalComplete[2]) {
549 for (int i = 0; i < 3; i++) {
550 qCDebug(APMSensorsComponentControllerLog) << QString("Onboard compass call report #%1: succeed:fitness %2:%3").arg(i).arg(_rgCompassCalSucceeded[i]).arg(_rgCompassCalFitness[i]);
551 }
552 emit compass1CalFitnessChanged(_rgCompassCalFitness[0]);
553 emit compass2CalFitnessChanged(_rgCompassCalFitness[1]);
554 emit compass3CalFitnessChanged(_rgCompassCalFitness[2]);
555 emit compass1CalSucceededChanged(_rgCompassCalSucceeded[0]);
556 emit compass2CalSucceededChanged(_rgCompassCalSucceeded[1]);
557 emit compass3CalSucceededChanged(_rgCompassCalSucceeded[2]);
558 if (_rgCompassCalSucceeded[0] && _rgCompassCalSucceeded[1] && _rgCompassCalSucceeded[2]) {
559 _appendStatusLog(tr("All compasses calibrated successfully"));
560 _appendStatusLog(tr("YOU MUST REBOOT YOUR VEHICLE NOW FOR NEW SETTINGS TO TAKE AFFECT"));
561 _stopCalibration(StopCalibrationSuccessShowLog);
562 } else {
563 _appendStatusLog(tr("Compass calibration failed"));
564 _appendStatusLog(tr("YOU MUST REBOOT YOUR VEHICLE NOW AND RETRY COMPASS CALIBRATION PRIOR TO FLIGHT"));
565 _stopCalibration(StopCalibrationFailed);
566 }
567 } else if (additionalCompassCompleted) {
568 _appendStatusLog(tr("Continue rotating..."));
569 }
570}
571
572bool APMSensorsComponentController::_handleCmdLongAccelcalVehiclePos(const mavlink_command_long_t &commandLong)
573{
574 bool updateImages = false;
575
576 switch (static_cast<ACCELCAL_VEHICLE_POS>(static_cast<int>(commandLong.param1))) {
577 case ACCELCAL_VEHICLE_POS_LEVEL:
578 if (!_orientationCalDownSideInProgress) {
579 updateImages = true;
580 _orientationCalDownSideInProgress = true;
581 _nextButton->setEnabled(true);
582 }
583 break;
584 case ACCELCAL_VEHICLE_POS_LEFT:
585 if (!_orientationCalLeftSideInProgress) {
586 updateImages = true;
587 _orientationCalDownSideDone = true;
588 _orientationCalDownSideInProgress = false;
589 _orientationCalLeftSideInProgress = true;
590 (void) _progressBar->setProperty("value", static_cast<qreal>(17 / 100.0));
591 }
592 break;
593 case ACCELCAL_VEHICLE_POS_RIGHT:
594 if (!_orientationCalRightSideInProgress) {
595 updateImages = true;
596 _orientationCalLeftSideDone = true;
597 _orientationCalLeftSideInProgress = false;
598 _orientationCalRightSideInProgress = true;
599 (void) _progressBar->setProperty("value", static_cast<qreal>(34 / 100.0));
600 }
601 break;
602 case ACCELCAL_VEHICLE_POS_NOSEDOWN:
603 if (!_orientationCalNoseDownSideInProgress) {
604 updateImages = true;
605 _orientationCalRightSideDone = true;
606 _orientationCalRightSideInProgress = false;
607 _orientationCalNoseDownSideInProgress = true;
608 (void) _progressBar->setProperty("value", static_cast<qreal>(51 / 100.0));
609 }
610 break;
611 case ACCELCAL_VEHICLE_POS_NOSEUP:
612 if (!_orientationCalTailDownSideInProgress) {
613 updateImages = true;
614 _orientationCalNoseDownSideDone = true;
615 _orientationCalNoseDownSideInProgress = false;
616 _orientationCalTailDownSideInProgress = true;
617 (void) _progressBar->setProperty("value", static_cast<qreal>(68 / 100.0));
618 }
619 break;
620 case ACCELCAL_VEHICLE_POS_BACK:
621 if (!_orientationCalUpsideDownSideInProgress) {
622 updateImages = true;
623 _orientationCalTailDownSideDone = true;
624 _orientationCalTailDownSideInProgress = false;
625 _orientationCalUpsideDownSideInProgress = true;
626 (void) _progressBar->setProperty("value", static_cast<qreal>(85 / 100.0));
627 }
628 break;
629 case ACCELCAL_VEHICLE_POS_SUCCESS:
630 _stopCalibration(StopCalibrationSuccess);
631 break;
632 case ACCELCAL_VEHICLE_POS_FAILED:
633 _stopCalibration(StopCalibrationFailed);
634 break;
635 case ACCELCAL_VEHICLE_POS_ENUM_END:
636 default:
637 break;
638 }
639
640 return updateImages;
641}
642
643void APMSensorsComponentController::_handleCommandLong(const mavlink_message_t &message)
644{
645 bool updateImages = false;
646 mavlink_command_long_t commandLong{};
647
648 mavlink_msg_command_long_decode(&message, &commandLong);
649
650 if (commandLong.command == MAV_CMD_ACCELCAL_VEHICLE_POS) {
651 updateImages = _handleCmdLongAccelcalVehiclePos(commandLong);
652 }
653
654 if (updateImages) {
658 }
659}
660
661void APMSensorsComponentController::_mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message)
662{
663 Q_UNUSED(link);
664
665 if (message.sysid != _vehicle->id()) {
666 return;
667 }
668
669 switch (message.msgid) {
670 case MAVLINK_MSG_ID_COMMAND_ACK:
671 _handleCommandAck(message);
672 break;
673 case MAVLINK_MSG_ID_MAG_CAL_PROGRESS:
674 _handleMagCalProgress(message);
675 break;
676 case MAVLINK_MSG_ID_MAG_CAL_REPORT:
677 _handleMagCalReport(message);
678 break;
679 case MAVLINK_MSG_ID_COMMAND_LONG:
680 _handleCommandLong(message);
681 break;
682 }
683}
684
685void APMSensorsComponentController::_restorePreviousCompassCalFitness()
686{
687 if (_restoreCompassCalFitness) {
688 _restoreCompassCalFitness = false;
689 getParameterFact(ParameterManager::defaultComponentId, _compassCalFitnessParam)->setRawValue(_previousCompassCalFitness);
690 }
691}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_command_ack_t mavlink_command_ack_t
struct __mavlink_command_long_t mavlink_command_long_t
This is the AutoPilotPlugin implementation for the MAV_AUTOPILOT_ARDUPILOT type.
const QVariantList & vehicleComponents() override
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.
Q_INVOKABLE Fact * getParameterFact(int componentId, const QString &name, bool reportMissing=true) const
Q_INVOKABLE bool parameterExists(int componentId, const QString &name) const
A Fact is used to hold a single value within the system.
Definition Fact.h:17
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
The link interface defines the interface for all links used to communicate with the ground station ap...
static int getComponentId()
void messageReceived(LinkInterface *link, const mavlink_message_t &message)
static MAVLinkProtocol * instance()
int getSystemId() const
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.
A vehicle component is an object which abstracts the physical portion of a vehicle into a set of conf...
void setupCompleteChanged()
WeakLinkInterfacePtr primaryLink() const
void setCommunicationLostEnabled(bool communicationLostEnabled)
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:2146
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
int defaultComponentId() const
Definition Vehicle.h:670
ParameterManager * parameterManager()
Definition Vehicle.h:573
void startCalibration(QGCMAVLink::CalibrationType calType)
Definition Vehicle.cc:2325
void stopCalibration(bool showError)
Definition Vehicle.cc:2405
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9