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