12#include <QtCore/QVariant>
14QGC_LOGGING_CATEGORY(APMSensorsComponentControllerLog,
"AutoPilotPlugins.APMSensorsComponentController")
20 APMAutoPilotPlugin *
const apmPlugin = qobject_cast<APMAutoPilotPlugin*>(_vehicle->autopilotPlugin());
24 _sensorsComponent = qobject_cast<APMSensorsComponent*>(varVehicleComponent.value<
VehicleComponent*>());
25 if (_sensorsComponent) {
30 if (_sensorsComponent) {
33 qCWarning(APMSensorsComponentControllerLog) <<
"Sensors component is missing";
40 _restorePreviousCompassCalFitness();
43void APMSensorsComponentController::_appendStatusLog(
const QString &text)
47 const QString varText = text;
48 (void) QMetaObject::invokeMethod(_statusLog,
"append", varText);
51void APMSensorsComponentController::_startLogCalibration()
59 _nextButton->setEnabled(
true);
66void APMSensorsComponentController::_startVisualCalibration()
69 _cancelButton->setEnabled(
true);
70 _nextButton->setEnabled(
false);
72 _resetInternalState();
74 (void) _progressBar->setProperty(
"value", 0);
79void APMSensorsComponentController::_resetInternalState()
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;
105void APMSensorsComponentController::_stopCalibration(APMSensorsComponentController::StopCalibrationCode code)
113 _nextButton->setEnabled(
false);
114 _cancelButton->setEnabled(
false);
117 _restorePreviousCompassCalFitness();
120 if (code == StopCalibrationSuccess) {
121 _resetInternalState();
122 (void) _progressBar->setProperty(
"value", 1);
127 (void) _progressBar->setProperty(
"value", 0);
130 _waitingForCancel =
false;
136 case StopCalibrationSuccess:
137 (void) _orientationCalAreaHelpText->setProperty(
"text", tr(
"Calibration complete"));
141 case StopCalibrationSuccessShowLog:
144 case StopCalibrationCancelled:
158void APMSensorsComponentController::_mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode)
160 Q_UNUSED(component); Q_UNUSED(failureCode);
167 case MAV_CMD_DO_CANCEL_MAG_CAL:
169 if (result == MAV_RESULT_ACCEPTED) {
172 _rgCompassCalProgress[0] = 0;
173 _rgCompassCalProgress[1] = 0;
174 _rgCompassCalProgress[2] = 0;
175 _rgCompassCalComplete[0] =
false;
176 _rgCompassCalComplete[1] =
false;
177 _rgCompassCalComplete[2] =
false;
179 _startLogCalibration();
180 uint8_t compassBits = 0;
183 compassBits |= 1 << 0;
184 qCDebug(APMSensorsComponentControllerLog) <<
"Performing onboard compass cal for compass 1";
186 _rgCompassCalComplete[0] =
true;
187 _rgCompassCalSucceeded[0] =
true;
188 _rgCompassCalFitness[0] = 0;
192 compassBits |= 1 << 1;
193 qCDebug(APMSensorsComponentControllerLog) <<
"Performing onboard compass cal for compass 2";
195 _rgCompassCalComplete[1] =
true;
196 _rgCompassCalSucceeded[1] =
true;
197 _rgCompassCalFitness[1] = 0;
201 compassBits |= 1 << 2;
202 qCDebug(APMSensorsComponentControllerLog) <<
"Performing onboard compass cal for compass 3";
204 _rgCompassCalComplete[2] =
true;
205 _rgCompassCalSucceeded[2] =
true;
206 _rgCompassCalFitness[2] = 0;
211 _restoreCompassCalFitness =
true;
212 _previousCompassCalFitness = compassCalFitness->
rawValue().toFloat();
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,
229 case MAV_CMD_DO_START_MAG_CAL:
230 if (result != MAV_RESULT_ACCEPTED) {
231 _restorePreviousCompassCalFitness();
234 case MAV_CMD_FIXED_MAG_CAL_YAW:
235 if (result == MAV_RESULT_ACCEPTED) {
236 _appendStatusLog(tr(
"Successfully completed"));
237 _stopCalibration(StopCalibrationSuccessShowLog);
239 _appendStatusLog(tr(
"Failed"));
240 _stopCalibration(StopCalibrationFailed);
260 _startLogCalibration();
268 if (doSimpleAccelCal) {
269 _startLogCalibration();
275 _startVisualCalibration();
276 _cancelButton->setEnabled(
false);
277 (void) _orientationCalAreaHelpText->setProperty(
"text", tr(
"Hold still in the current orientation and press Next when ready"));
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;
294 _orientationCalDownSideVisible =
false;
295 _orientationCalUpsideDownSideVisible =
false;
296 _orientationCalLeftSideVisible =
false;
297 _orientationCalRightSideVisible =
false;
298 _orientationCalTailDownSideVisible =
false;
299 _orientationCalNoseDownSideVisible =
false;
302 _orientationCalDownSideVisible =
true;
303 _orientationCalUpsideDownSideVisible =
true;
304 _orientationCalLeftSideVisible =
true;
305 _orientationCalRightSideVisible =
true;
306 _orientationCalTailDownSideVisible =
true;
307 _orientationCalNoseDownSideVisible =
true;
312 _updateAndEmitShowOrientationCalArea(
true);
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"));
332 _startLogCalibration();
333 _appendStatusLog(tr(
"Hold the vehicle in its level flight position."));
341 _startLogCalibration();
342 _appendStatusLog(tr(
"Requesting pressure calibration..."));
350 _startLogCalibration();
351 _appendStatusLog(tr(
"Requesting gyro calibration..."));
355void APMSensorsComponentController::_handleTextMessage(
int sysid,
int componentid,
int severity,
const QString &text,
const QString &description)
357 Q_UNUSED(componentid); Q_UNUSED(severity); Q_UNUSED(description);
363 const QString originalMessageText = text;
364 const QString messageText = text.toLower();
366 const QStringList hidePrefixList = { QStringLiteral(
"prearm:"), QStringLiteral(
"ekf"), QStringLiteral(
"arm"), QStringLiteral(
"initialising") };
367 for (
const QString &hidePrefix : hidePrefixList) {
368 if (messageText.startsWith(hidePrefix)) {
373 _appendStatusLog(originalMessageText);
374 qCDebug(APMSensorsComponentControllerLog) << originalMessageText << severity;
377void APMSensorsComponentController::_refreshParams()
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")
384 for (
const QString ¶mName : fastRefreshList) {
393void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(
bool show)
395 _showOrientationCalArea = show;
399void APMSensorsComponentController::_hideAllCalAreas()
401 _updateAndEmitShowOrientationCalArea(
false);
406 _cancelButton->setEnabled(
false);
410 _stopCalibration(StopCalibrationCancelled);
412 _waitingForCancel =
true;
426 (void) mavlink_msg_command_ack_pack_chan(
429 sharedLink->mavlinkChannel(),
442 _stopCalibration(StopCalibrationSuccess);
467void APMSensorsComponentController::_handleCommandAck(
const mavlink_message_t &message)
471 mavlink_msg_command_ack_decode(&message, &commandAck);
473 if (commandAck.command == MAV_CMD_PREFLIGHT_CALIBRATION) {
474 switch (commandAck.result) {
475 case MAV_RESULT_IN_PROGRESS:
476 _appendStatusLog(tr(
"In progress"));
478 case MAV_RESULT_ACCEPTED:
479 _appendStatusLog(tr(
"Successfully completed"));
480 _stopCalibration(StopCalibrationSuccessShowLog);
483 _appendStatusLog(tr(
"Failed"));
484 _stopCalibration(StopCalibrationFailed);
491void APMSensorsComponentController::_handleMagCalProgress(
const mavlink_message_t &message)
497 mavlink_mag_cal_progress_t magCalProgress{};
498 mavlink_msg_mag_cal_progress_decode(&message, &magCalProgress);
500 qCDebug(APMSensorsComponentControllerVerboseLog) <<
"id:mask:pct"
501 << magCalProgress.compass_id
502 << magCalProgress.cal_mask
503 << magCalProgress.completion_pct;
506 int compassCalCount = 0;
507 for (
int i = 0; i < 3; i++) {
508 if (magCalProgress.cal_mask & (1 << i)) {
513 if ((magCalProgress.compass_id < 3) && (compassCalCount != 0)) {
515 _rgCompassCalProgress[magCalProgress.compass_id] = magCalProgress.completion_pct / compassCalCount;
519 (void) _progressBar->setProperty(
"value",
static_cast<float>(_rgCompassCalProgress[0] + _rgCompassCalProgress[1] + _rgCompassCalProgress[2]) / 100.0);
523void APMSensorsComponentController::_handleMagCalReport(
const mavlink_message_t &message)
529 mavlink_mag_cal_report_t magCalReport{};
530 mavlink_msg_mag_cal_report_decode(&message, &magCalReport);
532 qCDebug(APMSensorsComponentControllerVerboseLog) <<
"id:mask:status:fitness"
533 << magCalReport.compass_id << magCalReport.cal_mask << magCalReport.cal_status << magCalReport.fitness;
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));
540 _appendStatusLog(tr(
"Compass %1 calibration below quality threshold").arg(magCalReport.compass_id));
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;
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]);
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);
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);
567 }
else if (additionalCompassCompleted) {
568 _appendStatusLog(tr(
"Continue rotating..."));
572bool APMSensorsComponentController::_handleCmdLongAccelcalVehiclePos(
const mavlink_command_long_t &commandLong)
574 bool updateImages =
false;
576 switch (
static_cast<ACCELCAL_VEHICLE_POS
>(
static_cast<int>(commandLong.param1))) {
577 case ACCELCAL_VEHICLE_POS_LEVEL:
578 if (!_orientationCalDownSideInProgress) {
580 _orientationCalDownSideInProgress =
true;
581 _nextButton->setEnabled(
true);
584 case ACCELCAL_VEHICLE_POS_LEFT:
585 if (!_orientationCalLeftSideInProgress) {
587 _orientationCalDownSideDone =
true;
588 _orientationCalDownSideInProgress =
false;
589 _orientationCalLeftSideInProgress =
true;
590 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(17 / 100.0));
593 case ACCELCAL_VEHICLE_POS_RIGHT:
594 if (!_orientationCalRightSideInProgress) {
596 _orientationCalLeftSideDone =
true;
597 _orientationCalLeftSideInProgress =
false;
598 _orientationCalRightSideInProgress =
true;
599 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(34 / 100.0));
602 case ACCELCAL_VEHICLE_POS_NOSEDOWN:
603 if (!_orientationCalNoseDownSideInProgress) {
605 _orientationCalRightSideDone =
true;
606 _orientationCalRightSideInProgress =
false;
607 _orientationCalNoseDownSideInProgress =
true;
608 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(51 / 100.0));
611 case ACCELCAL_VEHICLE_POS_NOSEUP:
612 if (!_orientationCalTailDownSideInProgress) {
614 _orientationCalNoseDownSideDone =
true;
615 _orientationCalNoseDownSideInProgress =
false;
616 _orientationCalTailDownSideInProgress =
true;
617 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(68 / 100.0));
620 case ACCELCAL_VEHICLE_POS_BACK:
621 if (!_orientationCalUpsideDownSideInProgress) {
623 _orientationCalTailDownSideDone =
true;
624 _orientationCalTailDownSideInProgress =
false;
625 _orientationCalUpsideDownSideInProgress =
true;
626 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(85 / 100.0));
629 case ACCELCAL_VEHICLE_POS_SUCCESS:
630 _stopCalibration(StopCalibrationSuccess);
632 case ACCELCAL_VEHICLE_POS_FAILED:
633 _stopCalibration(StopCalibrationFailed);
635 case ACCELCAL_VEHICLE_POS_ENUM_END:
643void APMSensorsComponentController::_handleCommandLong(
const mavlink_message_t &message)
645 bool updateImages =
false;
648 mavlink_msg_command_long_decode(&message, &commandLong);
650 if (commandLong.command == MAV_CMD_ACCELCAL_VEHICLE_POS) {
651 updateImages = _handleCmdLongAccelcalVehiclePos(commandLong);
669 switch (message.msgid) {
670 case MAVLINK_MSG_ID_COMMAND_ACK:
671 _handleCommandAck(message);
673 case MAVLINK_MSG_ID_MAG_CAL_PROGRESS:
674 _handleMagCalProgress(message);
676 case MAVLINK_MSG_ID_MAG_CAL_REPORT:
677 _handleMagCalReport(message);
679 case MAVLINK_MSG_ID_COMMAND_LONG:
680 _handleCommandLong(message);
685void APMSensorsComponentController::_restorePreviousCompassCalFitness()
687 if (_restoreCompassCalFitness) {
688 _restoreCompassCalFitness =
false;
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 waitingForCancelChanged()
void compass3CalFitnessChanged(double compass3CalFitness)
void compass1CalFitnessChanged(double compass1CalFitness)
Q_INVOKABLE void nextClicked()
void showOrientationCalAreaChanged()
void compass2CalFitnessChanged(double compass2CalFitness)
Q_INVOKABLE void calibrateAccel(bool doSimpleAccelCal)
Q_INVOKABLE bool usingUDPLink() const
void compass2CalSucceededChanged(bool compass2CalSucceeded)
Q_INVOKABLE void cancelCalibration()
Q_INVOKABLE void calibrateMotorInterference()
~APMSensorsComponentController()
bool accelSetupNeeded() const
Q_INVOKABLE void calibrateCompass()
Q_INVOKABLE void levelHorizon()
void orientationCalSidesInProgressChanged()
void setAllCalButtonsEnabled(bool enabled)
void compass3CalSucceededChanged(bool compass3CalSucceeded)
void setupNeededChanged()
void compass1CalSucceededChanged(bool compass1CalSucceeded)
Q_INVOKABLE void calibrateGyro()
Q_INVOKABLE void calibratePressure()
void calibrationComplete(QGCMAVLink::CalibrationType calType)
void orientationCalSidesDoneChanged()
void resetStatusTextArea()
void orientationCalSidesRotateChanged()
bool compassSetupNeeded() const
void orientationCalSidesVisibleChanged()
bool accelSetupNeeded() const
bool compassSetupNeeded() const
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.
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
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()
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 ¶mName)
Request a refresh on the specific parameter.
@ CalibrationAPMPressureAirspeed
@ CalibrationAPMAccelSimple
@ CalibrationAPMCompassMot
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)
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
int defaultComponentId() const
ParameterManager * parameterManager()
void startCalibration(QGCMAVLink::CalibrationType calType)
void stopCalibration(bool showError)
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.