10#include <QtCore/QVariant>
12QGC_LOGGING_CATEGORY(APMSensorsComponentControllerLog,
"AutoPilotPlugins.APMSensorsComponentController")
18 APMAutoPilotPlugin *
const apmPlugin = qobject_cast<APMAutoPilotPlugin*>(_vehicle->autopilotPlugin());
21 for (
const QVariant &varVehicleComponent : apmPlugin->vehicleComponents()) {
22 _sensorsComponent = qobject_cast<APMSensorsComponent*>(varVehicleComponent.value<
VehicleComponent*>());
23 if (_sensorsComponent) {
28 if (_sensorsComponent) {
31 qCWarning(APMSensorsComponentControllerLog) <<
"Sensors component is missing";
36APMSensorsComponentController::~APMSensorsComponentController()
38 _restorePreviousCompassCalFitness();
41void APMSensorsComponentController::_appendStatusLog(
const QString &text)
45 const QString varText = text;
46 (void) QMetaObject::invokeMethod(_statusLog,
"append", varText);
49void APMSensorsComponentController::_startLogCalibration()
57 _nextButton->setEnabled(
true);
64void APMSensorsComponentController::_startVisualCalibration()
67 _cancelButton->setEnabled(
true);
68 _nextButton->setEnabled(
false);
70 _resetInternalState();
72 (void) _progressBar->setProperty(
"value", 0);
77void APMSensorsComponentController::_resetInternalState()
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;
103void APMSensorsComponentController::_stopCalibration(APMSensorsComponentController::StopCalibrationCode code)
111 _nextButton->setEnabled(
false);
112 _cancelButton->setEnabled(
false);
115 _restorePreviousCompassCalFitness();
118 if (code == StopCalibrationSuccess) {
119 _resetInternalState();
120 (void) _progressBar->setProperty(
"value", 1);
125 (void) _progressBar->setProperty(
"value", 0);
128 _waitingForCancel =
false;
134 case StopCalibrationSuccess:
135 (void) _orientationCalAreaHelpText->setProperty(
"text", tr(
"Calibration complete"));
139 case StopCalibrationSuccessShowLog:
142 case StopCalibrationCancelled:
149 qgcApp()->showAppMessage(tr(
"Calibration failed. Calibration log will be displayed."));
156void APMSensorsComponentController::_mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode)
158 Q_UNUSED(component); Q_UNUSED(failureCode);
165 case MAV_CMD_DO_CANCEL_MAG_CAL:
167 if (result == MAV_RESULT_ACCEPTED) {
170 _rgCompassCalProgress[0] = 0;
171 _rgCompassCalProgress[1] = 0;
172 _rgCompassCalProgress[2] = 0;
173 _rgCompassCalComplete[0] =
false;
174 _rgCompassCalComplete[1] =
false;
175 _rgCompassCalComplete[2] =
false;
177 _startLogCalibration();
178 uint8_t compassBits = 0;
181 compassBits |= 1 << 0;
182 qCDebug(APMSensorsComponentControllerLog) <<
"Performing onboard compass cal for compass 1";
184 _rgCompassCalComplete[0] =
true;
185 _rgCompassCalSucceeded[0] =
true;
186 _rgCompassCalFitness[0] = 0;
190 compassBits |= 1 << 1;
191 qCDebug(APMSensorsComponentControllerLog) <<
"Performing onboard compass cal for compass 2";
193 _rgCompassCalComplete[1] =
true;
194 _rgCompassCalSucceeded[1] =
true;
195 _rgCompassCalFitness[1] = 0;
199 compassBits |= 1 << 2;
200 qCDebug(APMSensorsComponentControllerLog) <<
"Performing onboard compass cal for compass 3";
202 _rgCompassCalComplete[2] =
true;
203 _rgCompassCalSucceeded[2] =
true;
204 _rgCompassCalFitness[2] = 0;
209 _restoreCompassCalFitness =
true;
210 _previousCompassCalFitness = compassCalFitness->rawValue().toFloat();
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,
227 case MAV_CMD_DO_START_MAG_CAL:
228 if (result != MAV_RESULT_ACCEPTED) {
229 _restorePreviousCompassCalFitness();
232 case MAV_CMD_FIXED_MAG_CAL_YAW:
233 if (result == MAV_RESULT_ACCEPTED) {
234 _appendStatusLog(tr(
"Successfully completed"));
235 _stopCalibration(StopCalibrationSuccessShowLog);
237 _appendStatusLog(tr(
"Failed"));
238 _stopCalibration(StopCalibrationFailed);
246void APMSensorsComponentController::calibrateCompass()
256void APMSensorsComponentController::calibrateCompassNorth(
float lat,
float lon,
int mask)
258 _startLogCalibration();
263void APMSensorsComponentController::calibrateAccel(
bool doSimpleAccelCal)
266 if (doSimpleAccelCal) {
267 _startLogCalibration();
273 _startVisualCalibration();
274 _cancelButton->setEnabled(
false);
275 (void) _orientationCalAreaHelpText->setProperty(
"text", tr(
"Hold still in the current orientation and press Next when ready"));
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;
292 _orientationCalDownSideVisible =
false;
293 _orientationCalUpsideDownSideVisible =
false;
294 _orientationCalLeftSideVisible =
false;
295 _orientationCalRightSideVisible =
false;
296 _orientationCalTailDownSideVisible =
false;
297 _orientationCalNoseDownSideVisible =
false;
300 _orientationCalDownSideVisible =
true;
301 _orientationCalUpsideDownSideVisible =
true;
302 _orientationCalLeftSideVisible =
true;
303 _orientationCalRightSideVisible =
true;
304 _orientationCalTailDownSideVisible =
true;
305 _orientationCalNoseDownSideVisible =
true;
310 _updateAndEmitShowOrientationCalArea(
true);
315void APMSensorsComponentController::calibrateMotorInterference()
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"));
326void APMSensorsComponentController::levelHorizon()
330 _startLogCalibration();
331 _appendStatusLog(tr(
"Hold the vehicle in its level flight position."));
335void APMSensorsComponentController::calibratePressure()
339 _startLogCalibration();
340 _appendStatusLog(tr(
"Requesting pressure calibration..."));
344void APMSensorsComponentController::calibrateGyro()
348 _startLogCalibration();
349 _appendStatusLog(tr(
"Requesting gyro calibration..."));
353void APMSensorsComponentController::_handleTextMessage(
int sysid,
int componentid,
int severity,
const QString &text,
const QString &description)
355 Q_UNUSED(componentid); Q_UNUSED(severity); Q_UNUSED(description);
361 const QString originalMessageText = text;
362 const QString messageText = text.toLower();
364 const QStringList hidePrefixList = { QStringLiteral(
"prearm:"), QStringLiteral(
"ekf"), QStringLiteral(
"arm"), QStringLiteral(
"initialising") };
365 for (
const QString &hidePrefix : hidePrefixList) {
366 if (messageText.startsWith(hidePrefix)) {
371 _appendStatusLog(originalMessageText);
372 qCDebug(APMSensorsComponentControllerLog) << originalMessageText << severity;
375void APMSensorsComponentController::_refreshParams()
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")
382 for (
const QString ¶mName : fastRefreshList) {
391void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(
bool show)
393 _showOrientationCalArea = show;
397void APMSensorsComponentController::_hideAllCalAreas()
399 _updateAndEmitShowOrientationCalArea(
false);
402void APMSensorsComponentController::cancelCalibration()
404 _cancelButton->setEnabled(
false);
408 _stopCalibration(StopCalibrationCancelled);
410 _waitingForCancel =
true;
418void APMSensorsComponentController::nextClicked()
424 (void) mavlink_msg_command_ack_pack_chan(
427 sharedLink->mavlinkChannel(),
440 _stopCalibration(StopCalibrationSuccess);
445bool APMSensorsComponentController::compassSetupNeeded()
const
450bool APMSensorsComponentController::accelSetupNeeded()
const
455bool APMSensorsComponentController::usingUDPLink()
const
462 return (sharedLink->linkConfiguration()->type() == LinkConfiguration::TypeUdp);
465void APMSensorsComponentController::_handleCommandAck(
const mavlink_message_t &message)
468 mavlink_command_ack_t commandAck{};
469 mavlink_msg_command_ack_decode(&message, &commandAck);
471 if (commandAck.command == MAV_CMD_PREFLIGHT_CALIBRATION) {
472 switch (commandAck.result) {
473 case MAV_RESULT_IN_PROGRESS:
474 _appendStatusLog(tr(
"In progress"));
476 case MAV_RESULT_ACCEPTED:
477 _appendStatusLog(tr(
"Successfully completed"));
478 _stopCalibration(StopCalibrationSuccessShowLog);
481 _appendStatusLog(tr(
"Failed"));
482 _stopCalibration(StopCalibrationFailed);
489void APMSensorsComponentController::_handleMagCalProgress(
const mavlink_message_t &message)
495 mavlink_mag_cal_progress_t magCalProgress{};
496 mavlink_msg_mag_cal_progress_decode(&message, &magCalProgress);
498 qCDebug(APMSensorsComponentControllerVerboseLog) <<
"id:mask:pct"
499 << magCalProgress.compass_id
500 << magCalProgress.cal_mask
501 << magCalProgress.completion_pct;
504 int compassCalCount = 0;
505 for (
int i = 0; i < 3; i++) {
506 if (magCalProgress.cal_mask & (1 << i)) {
511 if ((magCalProgress.compass_id < 3) && (compassCalCount != 0)) {
513 _rgCompassCalProgress[magCalProgress.compass_id] = magCalProgress.completion_pct / compassCalCount;
517 (void) _progressBar->setProperty(
"value",
static_cast<float>(_rgCompassCalProgress[0] + _rgCompassCalProgress[1] + _rgCompassCalProgress[2]) / 100.0);
521void APMSensorsComponentController::_handleMagCalReport(
const mavlink_message_t &message)
527 mavlink_mag_cal_report_t magCalReport{};
528 mavlink_msg_mag_cal_report_decode(&message, &magCalReport);
530 qCDebug(APMSensorsComponentControllerVerboseLog) <<
"id:mask:status:fitness"
531 << magCalReport.compass_id << magCalReport.cal_mask << magCalReport.cal_status << magCalReport.fitness;
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));
538 _appendStatusLog(tr(
"Compass %1 calibration below quality threshold").arg(magCalReport.compass_id));
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;
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]);
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);
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);
565 }
else if (additionalCompassCompleted) {
566 _appendStatusLog(tr(
"Continue rotating..."));
570bool APMSensorsComponentController::_handleCmdLongAccelcalVehiclePos(
const mavlink_command_long_t &commandLong)
572 bool updateImages =
false;
574 switch (
static_cast<ACCELCAL_VEHICLE_POS
>(
static_cast<int>(commandLong.param1))) {
575 case ACCELCAL_VEHICLE_POS_LEVEL:
576 if (!_orientationCalDownSideInProgress) {
578 _orientationCalDownSideInProgress =
true;
579 _nextButton->setEnabled(
true);
582 case ACCELCAL_VEHICLE_POS_LEFT:
583 if (!_orientationCalLeftSideInProgress) {
585 _orientationCalDownSideDone =
true;
586 _orientationCalDownSideInProgress =
false;
587 _orientationCalLeftSideInProgress =
true;
588 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(17 / 100.0));
591 case ACCELCAL_VEHICLE_POS_RIGHT:
592 if (!_orientationCalRightSideInProgress) {
594 _orientationCalLeftSideDone =
true;
595 _orientationCalLeftSideInProgress =
false;
596 _orientationCalRightSideInProgress =
true;
597 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(34 / 100.0));
600 case ACCELCAL_VEHICLE_POS_NOSEDOWN:
601 if (!_orientationCalNoseDownSideInProgress) {
603 _orientationCalRightSideDone =
true;
604 _orientationCalRightSideInProgress =
false;
605 _orientationCalNoseDownSideInProgress =
true;
606 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(51 / 100.0));
609 case ACCELCAL_VEHICLE_POS_NOSEUP:
610 if (!_orientationCalTailDownSideInProgress) {
612 _orientationCalNoseDownSideDone =
true;
613 _orientationCalNoseDownSideInProgress =
false;
614 _orientationCalTailDownSideInProgress =
true;
615 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(68 / 100.0));
618 case ACCELCAL_VEHICLE_POS_BACK:
619 if (!_orientationCalUpsideDownSideInProgress) {
621 _orientationCalTailDownSideDone =
true;
622 _orientationCalTailDownSideInProgress =
false;
623 _orientationCalUpsideDownSideInProgress =
true;
624 (void) _progressBar->setProperty(
"value",
static_cast<qreal
>(85 / 100.0));
627 case ACCELCAL_VEHICLE_POS_SUCCESS:
628 _stopCalibration(StopCalibrationSuccess);
630 case ACCELCAL_VEHICLE_POS_FAILED:
631 _stopCalibration(StopCalibrationFailed);
633 case ACCELCAL_VEHICLE_POS_ENUM_END:
641void APMSensorsComponentController::_handleCommandLong(
const mavlink_message_t &message)
643 bool updateImages =
false;
644 mavlink_command_long_t commandLong{};
646 mavlink_msg_command_long_decode(&message, &commandLong);
648 if (commandLong.command == MAV_CMD_ACCELCAL_VEHICLE_POS) {
649 updateImages = _handleCmdLongAccelcalVehiclePos(commandLong);
667 switch (message.msgid) {
668 case MAVLINK_MSG_ID_COMMAND_ACK:
669 _handleCommandAck(message);
671 case MAVLINK_MSG_ID_MAG_CAL_PROGRESS:
672 _handleMagCalProgress(message);
674 case MAVLINK_MSG_ID_MAG_CAL_REPORT:
675 _handleMagCalReport(message);
677 case MAVLINK_MSG_ID_COMMAND_LONG:
678 _handleCommandLong(message);
683void APMSensorsComponentController::_restorePreviousCompassCalFitness()
685 if (_restoreCompassCalFitness) {
686 _restoreCompassCalFitness =
false;
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
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 waitingForCancelChanged()
void compass3CalFitnessChanged(double compass3CalFitness)
void compass1CalFitnessChanged(double compass1CalFitness)
void showOrientationCalAreaChanged()
void compass2CalFitnessChanged(double compass2CalFitness)
void compass2CalSucceededChanged(bool compass2CalSucceeded)
void orientationCalSidesInProgressChanged()
void setAllCalButtonsEnabled(bool enabled)
void compass3CalSucceededChanged(bool compass3CalSucceeded)
void setupNeededChanged()
void compass1CalSucceededChanged(bool compass1CalSucceeded)
void calibrationComplete(QGCMAVLink::CalibrationType calType)
void orientationCalSidesDoneChanged()
void resetStatusTextArea()
void orientationCalSidesRotateChanged()
void orientationCalSidesVisibleChanged()
bool accelSetupNeeded() const
bool compassSetupNeeded() const
Used for handling missing Facts from C++ code.
A Fact is used to hold a single value within the system.
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 ¶mName)
Request a refresh on the specific parameter.
@ CalibrationAPMPressureAirspeed
@ CalibrationAPMAccelSimple
@ CalibrationAPMCompassMot
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)