diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 0f2f072d7e3b6ed4e636e3bb8e6f4dba9aca994e..6e629ff4ad9842d5c5959bbcfae467d4f231f0d7 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -64,6 +64,10 @@ src/AutoPilotPlugins/PX4/Images/VehicleNoseDown.png src/AutoPilotPlugins/PX4/Images/VehicleTailDown.png + src/AutoPilotPlugins/PX4/Images/VehicleDownRotate.png + src/AutoPilotPlugins/PX4/Images/VehicleLeftRotate.png + src/AutoPilotPlugins/PX4/Images/VehicleNoseDownRotate.png + src/AutoPilotPlugins/PX4/AirframeComponent.qml src/AutoPilotPlugins/PX4/Images/AirframeStandardPlane.png diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc index 5b523e983c42fa7f71876745e27ffedb25c005f9..90f78113aa9a5da65199ab0afb757534f0afd2d4 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc @@ -153,11 +153,11 @@ void FlightModesComponentController::setSendLiveRCSwitchRanges(bool start) _rgRCReversed[i] = floatReversed == -1.0f; } - _uas->startRadioControlCalibration(); + _uas->startCalibration(UASInterface::StartCalibrationRadio); connect(_uas, &UASInterface::remoteControlChannelRawChanged, this, &FlightModesComponentController::_remoteControlChannelRawChanged); } else { disconnect(_uas, &UASInterface::remoteControlChannelRawChanged, this, &FlightModesComponentController::_remoteControlChannelRawChanged); - _uas->endRadioControlCalibration(); + _uas->stopCalibration(); _initRcValues(); emit switchLiveRangeChanged(); } diff --git a/src/AutoPilotPlugins/PX4/Images/VehicleDownRotate.png b/src/AutoPilotPlugins/PX4/Images/VehicleDownRotate.png new file mode 100644 index 0000000000000000000000000000000000000000..4dbf238223c44aa386e3faa6ce364999f5e2035c Binary files /dev/null and b/src/AutoPilotPlugins/PX4/Images/VehicleDownRotate.png differ diff --git a/src/AutoPilotPlugins/PX4/Images/VehicleLeftRotate.png b/src/AutoPilotPlugins/PX4/Images/VehicleLeftRotate.png new file mode 100644 index 0000000000000000000000000000000000000000..eaeb62d2cf35a9904508b8062138ec2839c8020e Binary files /dev/null and b/src/AutoPilotPlugins/PX4/Images/VehicleLeftRotate.png differ diff --git a/src/AutoPilotPlugins/PX4/Images/VehicleNoseDownRotate.png b/src/AutoPilotPlugins/PX4/Images/VehicleNoseDownRotate.png new file mode 100644 index 0000000000000000000000000000000000000000..45f9650bf924e0bbc2aef4e598f49c4ed7d1e09c Binary files /dev/null and b/src/AutoPilotPlugins/PX4/Images/VehicleNoseDownRotate.png differ diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.qml b/src/AutoPilotPlugins/PX4/SensorsComponent.qml index 04c0cf992c7f4aa5dc790e0cbe4e2e68bd8ed58a..179834e17083cfd266962d0da66979be328824f0 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.qml +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.qml @@ -24,6 +24,7 @@ import QtQuick 2.2 import QtQuick.Controls 1.2 import QtQuick.Controls.Styles 1.2 +import QtQuick.Dialogs 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 @@ -66,6 +67,25 @@ Rectangle { "ROTATION_ROLL_270_YAW_270" ] + readonly property string statusTextAreaDefaultText: "Sensor config is a work in progress. Not all visuals for all calibration types fully implemented.\n\n" + + "For Compass calibration you will need to rotate your vehicle through a number of positions. For this calibration is is best " + + "to be connected to you vehicle via radio instead of USB since the USB cable will likely get in the way.\n\n" + + "For Gyroscope calibration you will need to place your vehicle right side up on solid surface and leave it still.\n\n" + + "For Accelerometer calibration you will need to place your vehicle on all six sides and hold it there for a few seconds.\n\n" + + "For Airspeed calibration you will need to keep your airspeed sensor out of any wind.\n\n" + + Fact { id: cal_mag0_id; name: "CAL_MAG0_ID" } + Fact { id: cal_mag1_id; name: "CAL_MAG1_ID" } + Fact { id: cal_mag2_id; name: "CAL_MAG2_ID" } + Fact { id: cal_mag0_rot; name: "CAL_MAG0_ROT" } + Fact { id: cal_mag1_rot; name: "CAL_MAG1_ROT" } + Fact { id: cal_mag2_rot; name: "CAL_MAG2_ROT" } + + // Id > = signals compass available, rot < 0 signals internal compass + property bool showCompass0Rot: cal_mag0_id.value > 0 && cal_mag0_rot.value >= 0 + property bool showCompass1Rot: cal_mag1_id.value > 0 && cal_mag1_rot.value >= 0 + property bool showCompass2Rot: cal_mag2_id.value > 0 && cal_mag2_rot.value >= 0 + color: qgcPal.window // We use this bogus loader just so we can get an onLoaded signal to hook to in order to @@ -83,6 +103,227 @@ Rectangle { controller.gyroButton = gyroButton controller.accelButton = accelButton controller.airspeedButton = airspeedButton + controller.cancelButton = cancelButton + controller.orientationCalAreaHelpText = orientationCalAreaHelpText + } + } + + Connections { + target: controller + + onResetStatusTextArea: statusTextArea.text = statusTextAreaDefaultText + onSetCompassRotations: showCompassRotationOverlay() + } + + Rectangle { + id: overlay + anchors.fill: parent + color: qgcPal.window + opacity: 0.75 + z: 100 + visible: false + } + + Rectangle { + width: 300 + height: 100 + anchors.verticalCenter: parent.verticalCenter + anchors.horizontalCenter: parent.horizontalCenter + color: qgcPal.window + border.width: 1 + border.color: qgcPal.text + visible: controller.waitingForCancel + z: overlay.z + 1 + + onVisibleChanged: { + overlay.visible = visible + } + + QGCLabel { + anchors.fill: parent + verticalAlignment: Text.AlignVCenter + horizontalAlignment: Text.AlignHCenter + text: "Waiting for Cancel (may take a few seconds)" + } + } + + Rectangle { + property string calibrationType + + id: boardRotationOverlay + width: 300 + height: boardRotationOverlayColumn.height + 11 + anchors.verticalCenter: parent.verticalCenter + anchors.horizontalCenter: parent.horizontalCenter + color: qgcPal.window + border.width: 1 + border.color: qgcPal.text + visible: false + z: overlay.z + 1 + + Column { + id: boardRotationOverlayColumn + anchors.topMargin: 10 + anchors.top: parent.top + width: parent.width + spacing: 10 + + Column { + anchors.leftMargin: 10 + anchors.rightMargin: 10 + anchors.left: parent.left + anchors.right: parent.right + spacing: 10 + + QGCLabel { + width: parent.width + wrapMode: Text.WordWrap + text: "Please check and/or update board rotation before calibrating" + } + + FactComboBox { + width: rotationColumnWidth + model: rotations + fact: Fact { name: "SENS_BOARD_ROT" } + } + } + + QGCButton { + x: 1 + width: parent.width - 2 + primary: true + text: "OK" + + onClicked: { + boardRotationOverlay.visible = false + overlay.visible = false + + if (boardRotationOverlay.calibrationType == "gyro") { + controller.calibrateGyro() + } else if (boardRotationOverlay.calibrationType == "accel") { + controller.calibrateAccel() + } else if (boardRotationOverlay.calibrationType == "compass") { + controller.calibrateCompass() + } + } + } + } + } + + function showBoardRotationOverlay(calibrationType) { + boardRotationOverlay.calibrationType = calibrationType + boardRotationOverlay.visible = true + overlay.visible = true + } + + Rectangle { + id: compassRotationOverlay + width: 300 + height: compassRotationOverlayColumn.height + 11 + anchors.verticalCenter: parent.verticalCenter + anchors.horizontalCenter: parent.horizontalCenter + color: qgcPal.window + border.width: 1 + border.color: qgcPal.text + visible: false + z: overlay.z + 1 + + Column { + id: compassRotationOverlayColumn + anchors.topMargin: 10 + anchors.top: parent.top + width: parent.width + spacing: 10 + + Column { + anchors.leftMargin: 10 + anchors.rightMargin: 10 + anchors.left: parent.left + anchors.right: parent.right + spacing: 10 + + QGCLabel { + width: parent.width + wrapMode: Text.WordWrap + text: "Please check and/or update compass rotation(s)" + } + + // Compass 0 rotation + Component { + id: compass0ComponentLabel + + QGCLabel { text: "Compass Orientation" } + } + Component { + id: compass0ComponentCombo + + FactComboBox { + id: compass0RotationCombo + width: rotationColumnWidth + model: rotations + fact: Fact { name: "CAL_MAG0_ROT" } + } + } + Loader { sourceComponent: showCompass0Rot ? compass0ComponentLabel : null } + Loader { sourceComponent: showCompass0Rot ? compass0ComponentCombo : null } + + // Compass 1 rotation + Component { + id: compass1ComponentLabel + + QGCLabel { text: "Compass 1 Orientation" } + } + Component { + id: compass1ComponentCombo + + FactComboBox { + id: compass1RotationCombo + width: rotationColumnWidth + model: rotations + fact: Fact { name: "CAL_MAG1_ROT" } + } + } + Loader { sourceComponent: showCompass1Rot ? compass1ComponentLabel : null } + Loader { sourceComponent: showCompass1Rot ? compass1ComponentCombo : null } + + // Compass 2 rotation + Component { + id: compass2ComponentLabel + + QGCLabel { text: "Compass 2 Orientation" } + } + Component { + id: compass2ComponentCombo + + FactComboBox { + id: compass1RotationCombo + width: rotationColumnWidth + model: rotations + fact: Fact { name: "CAL_MAG2_ROT" } + } + } + Loader { sourceComponent: showCompass2Rot ? compass2ComponentLabel : null } + Loader { sourceComponent: showCompass2Rot ? compass2ComponentCombo : null } + } + + QGCButton { + x: 1 + width: parent.width - 2 + primary: true + text: "OK" + + onClicked: { + compassRotationOverlay.visible = false + overlay.visible = false + } + } + } + } + + function showCompassRotationOverlay() { + if (showCompass0Rot || showCompass1Rot || showCompass2Rot) { + compassRotationOverlay.visible = true + overlay.visible = true } } @@ -110,7 +351,8 @@ Rectangle { width: parent.buttonWidth text: "Compass" indicatorGreen: fact.value != 0 - onClicked: controller.calibrateCompass() + + onClicked: showBoardRotationOverlay("compass") } IndicatorButton { @@ -120,7 +362,8 @@ Rectangle { width: parent.buttonWidth text: "Gyroscope" indicatorGreen: fact.value != 0 - onClicked: controller.calibrateGyro() + + onClicked: showBoardRotationOverlay("gyro") } IndicatorButton { @@ -130,7 +373,8 @@ Rectangle { width: parent.buttonWidth text: "Accelerometer" indicatorGreen: fact.value != 0 - onClicked: controller.calibrateAccel() + + onClicked: showBoardRotationOverlay("accel") } IndicatorButton { @@ -143,6 +387,13 @@ Rectangle { indicatorGreen: fact.value != 0 onClicked: controller.calibrateAirspeed() } + + QGCButton { + id: cancelButton + text: "Cancel" + enabled: false + onClicked: controller.cancelCalibration() + } } Item { height: 20; width: 10 } // spacer @@ -167,12 +418,7 @@ Rectangle { height: parent.height readOnly: true frameVisible: false - text: "Sensor config is a work in progress. Not all visuals for all calibration types fully implemented.\n\n" + - "For Compass calibration you will need to rotate your vehicle through a number of positions. For this calibration is is best " + - "to be connected to you vehicle via radio instead of USB since the USB cable will likely get in the way.\n\n" + - "For Gyroscope calibration you will need to place your vehicle right side up on solid surface and leave it still.\n\n" + - "For Accelerometer calibration you will need to place your vehicle on all six sides and hold it there for a few seconds.\n\n" + - "For Airspeed calibration you will need to keep your airspeed sensor out of any wind.\n\n" + text: statusTextAreaDefaultText style: TextAreaStyle { textColor: qgcPal.text @@ -180,29 +426,6 @@ Rectangle { } } - Rectangle { - id: gyroCalArea - width: parent.calDisplayAreaWidth - height: parent.height - visible: controller.showGyroCalArea - color: qgcPal.windowShade - - Column { - width: parent.width - - QGCLabel { - text: "Place your vehicle upright on a solid surface and hold it still." - } - - VehicleRotationCal { - calValid: true - calInProgress: controller.gyroCalInProgress - imageSource: "qrc:///qml/VehicleDown.png" - } - - } - } - Rectangle { id: orientationCalArea width: parent.calDisplayAreaWidth @@ -211,53 +434,58 @@ Rectangle { color: qgcPal.windowShade QGCLabel { - id: calAreaLabel - width: parent.width - wrapMode: Text.WordWrap - - text: "Place your vehicle into each of the positions below and hold still. Once that position is completed you can move to another." + id: orientationCalAreaHelpText + width: parent.width + wrapMode: Text.WordWrap + font.pointSize: screenTools.fontPointFactor * (17); } Flow { - y: calAreaLabel.height + y: orientationCalAreaHelpText.height width: parent.width - height: parent.height - calAreaLabel.implicitHeight + height: parent.height - orientationCalAreaHelpText.implicitHeight spacing: 5 VehicleRotationCal { + visible: controller.orientationCalDownSideVisible calValid: controller.orientationCalDownSideDone calInProgress: controller.orientationCalDownSideInProgress - calInProgressText: controller.calInProgressText - imageSource: "qrc:///qml/VehicleDown.png" + calInProgressText: controller.orientationCalDownSideRotate ? "Rotate" : "Hold Still" + imageSource: controller.orientationCalDownSideRotate ? "qrc:///qml/VehicleDownRotate.png" : "qrc:///qml/VehicleDown.png" } VehicleRotationCal { + visible: controller.orientationCalUpsideDownSideVisible calValid: controller.orientationCalUpsideDownSideDone calInProgress: controller.orientationCalUpsideDownSideInProgress - calInProgressText: controller.calInProgressText + calInProgressText: "Hold Still" imageSource: "qrc:///qml/VehicleUpsideDown.png" } VehicleRotationCal { + visible: controller.orientationCalNoseDownSideVisible calValid: controller.orientationCalNoseDownSideDone calInProgress: controller.orientationCalNoseDownSideInProgress - calInProgressText: controller.calInProgressText - imageSource: "qrc:///qml/VehicleNoseDown.png" + calInProgressText: controller.orientationCalNoseDownSideRotate ? "Rotate" : "Hold Still" + imageSource: controller.orientationCalNoseDownSideRotate ? "qrc:///qml/VehicleNoseDownRotate.png" : "qrc:///qml/VehicleNoseDown.png" } VehicleRotationCal { + visible: controller.orientationCalTailDownSideVisible calValid: controller.orientationCalTailDownSideDone calInProgress: controller.orientationCalTailDownSideInProgress - calInProgressText: controller.calInProgressText + calInProgressText: "Hold Still" imageSource: "qrc:///qml/VehicleTailDown.png" } VehicleRotationCal { + visible: controller.orientationCalLeftSideVisible calValid: controller.orientationCalLeftSideDone calInProgress: controller.orientationCalLeftSideInProgress - calInProgressText: controller.calInProgressText - imageSource: "qrc:///qml/VehicleLeft.png" + calInProgressText: controller.orientationCalLeftSideRotate ? "Rotate" : "Hold Still" + imageSource: controller.orientationCalLeftSideRotate ? "qrc:///qml/VehicleLeftRotate.png" : "qrc:///qml/VehicleLeft.png" } VehicleRotationCal { + visible: controller.orientationCalRightSideVisible calValid: controller.orientationCalRightSideDone calInProgress: controller.orientationCalRightSideInProgress - calInProgressText: controller.calInProgressText + calInProgressText: "Hold Still" imageSource: "qrc:///qml/VehicleRight.png" } } @@ -277,12 +505,12 @@ Rectangle { // Compass 0 rotation Component { - id: compass0ComponentLabel + id: compass0ComponentLabel2 QGCLabel { text: "Compass Orientation" } } Component { - id: compass0ComponentCombo + id: compass0ComponentCombo2 FactComboBox { id: compass0RotationCombo @@ -291,17 +519,17 @@ Rectangle { fact: Fact { name: "CAL_MAG0_ROT" } } } - Loader { sourceComponent: controller.showCompass0 ? compass0ComponentLabel : null } - Loader { sourceComponent: controller.showCompass0 ? compass0ComponentCombo : null } + Loader { sourceComponent: showCompass0Rot ? compass0ComponentLabel2 : null } + Loader { sourceComponent: showCompass0Rot ? compass0ComponentCombo2 : null } // Compass 1 rotation Component { - id: compass1ComponentLabel + id: compass1ComponentLabel2 QGCLabel { text: "Compass 1 Orientation" } } Component { - id: compass1ComponentCombo + id: compass1ComponentCombo2 FactComboBox { id: compass1RotationCombo @@ -310,17 +538,17 @@ Rectangle { fact: Fact { name: "CAL_MAG1_ROT" } } } - Loader { sourceComponent: controller.showCompass1 ? compass1ComponentLabel : null } - Loader { sourceComponent: controller.showCompass1 ? compass1ComponentCombo : null } + Loader { sourceComponent: showCompass1Rot ? compass1ComponentLabel2 : null } + Loader { sourceComponent: showCompass1Rot ? compass1ComponentCombo2 : null } // Compass 2 rotation Component { - id: compass2ComponentLabel + id: compass2ComponentLabel2 QGCLabel { text: "Compass 2 Orientation" } } Component { - id: compass2ComponentCombo + id: compass2ComponentCombo2 FactComboBox { id: compass1RotationCombo @@ -329,8 +557,8 @@ Rectangle { fact: Fact { name: "CAL_MAG2_ROT" } } } - Loader { sourceComponent: controller.showCompass2 ? compass2ComponentLabel : null } - Loader { sourceComponent: controller.showCompass2 ? compass2ComponentCombo : null } + Loader { sourceComponent: showCompass2Rot ? compass2ComponentLabel2 : null } + Loader { sourceComponent: showCompass2Rot ? compass2ComponentCombo2 : null } } } } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index 9c131282435bced9bb1fe42dc7391ccf0ffb0d8b..9825238057fd3d26c02191493be7a1c1be987f97 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -36,11 +36,12 @@ SensorsComponentController::SensorsComponentController(AutoPilotPlugin* autopilo QObject(parent), _statusLog(NULL), _progressBar(NULL), - _showGyroCalArea(false), + _compassButton(NULL), + _gyroButton(NULL), + _accelButton(NULL), + _airspeedButton(NULL), + _cancelButton(NULL), _showOrientationCalArea(false), - _showCompass0(false), - _showCompass1(false), - _showCompass2(false), _gyroCalInProgress(false), _magCalInProgress(false), _accelCalInProgress(false), @@ -50,18 +51,31 @@ SensorsComponentController::SensorsComponentController(AutoPilotPlugin* autopilo _orientationCalRightSideDone(false), _orientationCalNoseDownSideDone(false), _orientationCalTailDownSideDone(false), + _orientationCalDownSideVisible(false), + _orientationCalUpsideDownSideVisible(false), + _orientationCalLeftSideVisible(false), + _orientationCalRightSideVisible(false), + _orientationCalNoseDownSideVisible(false), + _orientationCalTailDownSideVisible(false), _orientationCalDownSideInProgress(false), _orientationCalUpsideDownSideInProgress(false), _orientationCalLeftSideInProgress(false), _orientationCalRightSideInProgress(false), _orientationCalNoseDownSideInProgress(false), _orientationCalTailDownSideInProgress(false), - _textLoggingStarted(false), + _orientationCalDownSideRotate(false), + _orientationCalLeftSideRotate(false), + _orientationCalNoseDownSideRotate(false), + _unknownFirmwareVersion(false), + _waitingForCancel(false), _autopilot(autopilot) { Q_ASSERT(_autopilot); Q_ASSERT(_autopilot->pluginReady()); + _uas = _autopilot->uas(); + Q_ASSERT(_uas); + // Mag rotation parameters are optional _showCompass0 = _autopilot->parameterExists("CAL_MAG0_ROT") && _autopilot->getParameterFact("CAL_MAG0_ROT")->value().toInt() >= 0; @@ -84,89 +98,115 @@ void SensorsComponentController::_appendStatusLog(const QString& text) Q_ARG(QVariant, varText)); } -void SensorsComponentController::_startCalibration(void) +void SensorsComponentController::_startLogCalibration(void) { - _beginTextLogging(); + _unknownFirmwareVersion = false; _hideAllCalAreas(); + connect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage); + + _cancelButton->setEnabled(false); +} + +void SensorsComponentController::_startVisualCalibration(void) +{ _compassButton->setEnabled(false); _gyroButton->setEnabled(false); _accelButton->setEnabled(false); _airspeedButton->setEnabled(false); + _cancelButton->setEnabled(true); + + _progressBar->setProperty("value", 0); } -void SensorsComponentController::_stopCalibration(bool failed) +void SensorsComponentController::_stopCalibration(SensorsComponentController::StopCalibrationCode code) { - _magCalInProgress = false; - _accelCalInProgress = false; + disconnect(_uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage); _compassButton->setEnabled(true); _gyroButton->setEnabled(true); _accelButton->setEnabled(true); _airspeedButton->setEnabled(true); + _cancelButton->setEnabled(false); + + if (code == StopCalibrationSuccess) { + _orientationCalDownSideDone = true; + _orientationCalUpsideDownSideDone = true; + _orientationCalLeftSideDone = true; + _orientationCalRightSideDone = true; + _orientationCalTailDownSideDone = true; + _orientationCalNoseDownSideDone = true; + _orientationCalDownSideInProgress = false; + _orientationCalUpsideDownSideInProgress = false; + _orientationCalLeftSideInProgress = false; + _orientationCalRightSideInProgress = false; + _orientationCalNoseDownSideInProgress = false; + _orientationCalTailDownSideInProgress = false; + emit orientationCalSidesDoneChanged(); + emit orientationCalSidesInProgressChanged(); + + _progressBar->setProperty("value", 1); + } else { + _progressBar->setProperty("value", 0); + } - _progressBar->setProperty("value", failed ? 0 : 1); - _updateAndEmitGyroCalInProgress(false); + _waitingForCancel = false; + emit waitingForCancelChanged(); + _refreshParams(); - if (failed) { - QGCMessageBox::warning("Calibration", "Calibration failed. Calibration log will be displayed."); - _hideAllCalAreas(); + switch (code) { + case StopCalibrationSuccess: + _orientationCalAreaHelpText->setProperty("text", "Calibration complete"); + emit resetStatusTextArea(); + if (_magCalInProgress) { + emit setCompassRotations(); + } + break; + + case StopCalibrationCancelled: + emit resetStatusTextArea(); + _hideAllCalAreas(); + break; + + default: + // Assume failed + _hideAllCalAreas(); + QGCMessageBox::warning("Calibration", "Calibration failed. Calibration log will be displayed."); + break; } + + _magCalInProgress = false; + _accelCalInProgress = false; + _gyroCalInProgress = false; } void SensorsComponentController::calibrateGyro(void) { - _startCalibration(); - - UASInterface* uas = _autopilot->uas(); - Q_ASSERT(uas); - uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0); + _startLogCalibration(); + _uas->startCalibration(UASInterface::StartCalibrationGyro); } void SensorsComponentController::calibrateCompass(void) { - _startCalibration(); - - UASInterface* uas = _autopilot->uas(); - Q_ASSERT(uas); - uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0); + _startLogCalibration(); + _uas->startCalibration(UASInterface::StartCalibrationMag); } void SensorsComponentController::calibrateAccel(void) { - _startCalibration(); - - UASInterface* uas = _autopilot->uas(); - Q_ASSERT(uas); - uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0); + _startLogCalibration(); + _uas->startCalibration(UASInterface::StartCalibrationAccel); } void SensorsComponentController::calibrateAirspeed(void) { - _startCalibration(); - - UASInterface* uas = _autopilot->uas(); - Q_ASSERT(uas); - uas->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0); -} - -void SensorsComponentController::_beginTextLogging(void) -{ - if (!_textLoggingStarted) { - _textLoggingStarted = true; - UASInterface* uas = _autopilot->uas(); - Q_ASSERT(uas); - connect(uas, &UASInterface::textMessageReceived, this, &SensorsComponentController::_handleUASTextMessage); - } + _startLogCalibration(); + _uas->startCalibration(UASInterface::StartCalibrationAirspeed); } void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text) { - QString startingSidePrefix("Hold still, starting to measure "); - QString sideDoneSuffix(" side done, rotate to a different side"); - QString orientationDetectedSuffix(" orientation detected"); - Q_UNUSED(compId); Q_UNUSED(severity); @@ -176,14 +216,6 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in return; } - QStringList ignorePrefixList; - ignorePrefixList << "[cmd]" << "[mavlink pm]" << "[ekf check]" << "[pm]" << "[inav]" << "IN AIR MODE" << "LANDED MODE"; - foreach (QString ignorePrefix, ignorePrefixList) { - if (text.startsWith(ignorePrefix)) { - return; - } - } - if (text.contains("progress <")) { QString percent = text.split("<").last().split(">").first(); bool ok; @@ -196,138 +228,179 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in } _appendStatusLog(text); + qDebug() << text; + + if (_unknownFirmwareVersion) { + // We don't know how to do visual cal with the version of firwmare + return; + } + + // All calibration messages start with [cal] + QString calPrefix("[cal] "); + if (!text.startsWith(calPrefix)) { + return; + } + text = text.right(text.length() - calPrefix.length()); - if (text == "gyro calibration: started") { - _updateAndEmitShowGyroCalArea(true); - _updateAndEmitGyroCalInProgress(true); - } else if (text == "accel calibration: started" || text == "mag calibration: started") { - if (text == "accel calibration: started") { - _accelCalInProgress = true; - _updateAndEmitCalInProgressText("Hold Still"); - } else { - _updateAndEmitCalInProgressText("Rotate"); - _magCalInProgress = true; + QString calStartPrefix("calibration started: "); + if (text.startsWith(calStartPrefix)) { + text = text.right(text.length() - calStartPrefix.length()); + + // Split version number and cal type + QStringList parts = text.split(" "); + if (parts.count() != 2 && parts[0].toInt() != 1) { + _unknownFirmwareVersion = true; + qDebug() << "Unknown cal firmware version, using log"; + return; } - _orientationCalDownSideDone = false; - _orientationCalUpsideDownSideDone = false; - _orientationCalLeftSideDone = false; - _orientationCalRightSideDone = false; - _orientationCalTailDownSideDone = false; - _orientationCalNoseDownSideDone = false; - _orientationCalDownSideInProgress = false; - _orientationCalUpsideDownSideInProgress = false; - _orientationCalLeftSideInProgress = false; - _orientationCalRightSideInProgress = false; - _orientationCalNoseDownSideInProgress = false; - _orientationCalTailDownSideInProgress = false; - emit orientationCalSidesDoneChanged(); - emit orientationCalSidesInProgressChanged(); - _updateAndEmitShowOrientationCalArea(true); - } else if (text.startsWith(startingSidePrefix)) { - QString side = text.right(text.length() - startingSidePrefix.length()).section(" ", 0, 0); - qDebug() << "Side started" << side; - if (side == "down") { - _orientationCalDownSideInProgress = true; - } else if (side == "up") { - _orientationCalUpsideDownSideInProgress = true; - } else if (side == "left") { - _orientationCalLeftSideInProgress = true; - } else if (side == "right") { - _orientationCalRightSideInProgress = true; - } else if (side == "front") { - _orientationCalNoseDownSideInProgress = true; - } else if (side == "back") { - _orientationCalTailDownSideInProgress = true; + + _startVisualCalibration(); + + text = parts[1]; + if (text == "accel" || text == "mag" || text == "gyro") { + // Reset all progress indication + _orientationCalDownSideDone = false; + _orientationCalUpsideDownSideDone = false; + _orientationCalLeftSideDone = false; + _orientationCalRightSideDone = false; + _orientationCalTailDownSideDone = false; + _orientationCalNoseDownSideDone = false; + _orientationCalDownSideInProgress = false; + _orientationCalUpsideDownSideInProgress = false; + _orientationCalLeftSideInProgress = false; + _orientationCalRightSideInProgress = false; + _orientationCalNoseDownSideInProgress = false; + _orientationCalTailDownSideInProgress = false; + + // Reset all visibility + _orientationCalDownSideVisible = false; + _orientationCalUpsideDownSideVisible = false; + _orientationCalLeftSideVisible = false; + _orientationCalRightSideVisible = false; + _orientationCalTailDownSideVisible = false; + _orientationCalNoseDownSideVisible = false; + + _orientationCalAreaHelpText->setProperty("text", "Place your vehicle into one of the Incomplete orientations shown below and hold it still"); + + if (text == "accel") { + _accelCalInProgress = true; + _orientationCalDownSideVisible = true; + _orientationCalUpsideDownSideVisible = true; + _orientationCalLeftSideVisible = true; + _orientationCalRightSideVisible = true; + _orientationCalTailDownSideVisible = true; + _orientationCalNoseDownSideVisible = true; + } else if (text == "mag") { + _magCalInProgress = true; + _orientationCalDownSideVisible = true; + _orientationCalLeftSideVisible = true; + _orientationCalNoseDownSideVisible = true; + } else if (text == "gyro") { + _gyroCalInProgress = true; + _orientationCalDownSideVisible = true; + } else { + Q_ASSERT(false); + } + emit orientationCalSidesDoneChanged(); + emit orientationCalSidesVisibleChanged(); + emit orientationCalSidesInProgressChanged(); + _updateAndEmitShowOrientationCalArea(true); } - emit orientationCalSidesInProgressChanged(); - } else if (text.endsWith(orientationDetectedSuffix)) { + return; + } + + if (text.endsWith("orientation detected")) { QString side = text.section(" ", 0, 0); qDebug() << "Side started" << side; + if (side == "down") { _orientationCalDownSideInProgress = true; + if (_magCalInProgress) { + _orientationCalDownSideRotate = true; + } } else if (side == "up") { _orientationCalUpsideDownSideInProgress = true; } else if (side == "left") { _orientationCalLeftSideInProgress = true; + if (_magCalInProgress) { + _orientationCalLeftSideRotate = true; + } } else if (side == "right") { _orientationCalRightSideInProgress = true; } else if (side == "front") { _orientationCalNoseDownSideInProgress = true; + if (_magCalInProgress) { + _orientationCalNoseDownSideRotate = true; + } } else if (side == "back") { _orientationCalTailDownSideInProgress = true; } + + if (_magCalInProgress) { + _orientationCalAreaHelpText->setProperty("text", "Rotate the vehicle continuously as shown in the diagram until marked as Completed"); + } else { + _orientationCalAreaHelpText->setProperty("text", "Hold still in the current orientation"); + } + emit orientationCalSidesInProgressChanged(); - } else if (text.endsWith(sideDoneSuffix)) { + emit orientationCalSidesRotateChanged(); + return; + } + + if (text.endsWith("side done, rotate to a different side")) { QString side = text.section(" ", 0, 0); qDebug() << "Side finished" << side; + if (side == "down") { _orientationCalDownSideInProgress = false; _orientationCalDownSideDone = true; + _orientationCalDownSideRotate = false; } else if (side == "up") { _orientationCalUpsideDownSideInProgress = false; _orientationCalUpsideDownSideDone = true; } else if (side == "left") { _orientationCalLeftSideInProgress = false; _orientationCalLeftSideDone = true; + _orientationCalLeftSideRotate = false; } else if (side == "right") { _orientationCalRightSideInProgress = false; _orientationCalRightSideDone = true; } else if (side == "front") { _orientationCalNoseDownSideInProgress = false; _orientationCalNoseDownSideDone = true; + _orientationCalNoseDownSideRotate = false; } else if (side == "back") { _orientationCalTailDownSideInProgress = false; _orientationCalTailDownSideDone = true; } + + _orientationCalAreaHelpText->setProperty("text", "Place you vehicle into one of the orientations shown below and hold it still"); + emit orientationCalSidesInProgressChanged(); emit orientationCalSidesDoneChanged(); - } else if (text == "accel calibration: done" || text == "mag calibration: done") { - _progressBar->setProperty("value", 1); - _orientationCalDownSideDone = true; - _orientationCalUpsideDownSideDone = true; - _orientationCalLeftSideDone = true; - _orientationCalRightSideDone = true; - _orientationCalTailDownSideDone = true; - _orientationCalNoseDownSideDone = true; - _orientationCalDownSideInProgress = false; - _orientationCalUpsideDownSideInProgress = false; - _orientationCalLeftSideInProgress = false; - _orientationCalRightSideInProgress = false; - _orientationCalNoseDownSideInProgress = false; - _orientationCalTailDownSideInProgress = false; - emit orientationCalSidesDoneChanged(); - emit orientationCalSidesInProgressChanged(); - _stopCalibration(false /* success */); - } else if (text == "gyro calibration: done") { - _stopCalibration(false /* success */); - } else if (text == "dpress calibration: done") { - _stopCalibration(false /* success */); - } else if (text.endsWith(" calibration: failed")) { - _stopCalibration(true /* failed */); + emit orientationCalSidesRotateChanged(); + return; } -} - -void SensorsComponentController::_refreshParams(void) -{ - // Pull specified params first so red/green indicators update quickly - _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG0_ID"); - _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_GYRO0_ID"); - _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_ACC0_ID"); - _autopilot->refreshParameter(FactSystem::defaultComponentId, "SENS_DPRES_OFF"); - - _autopilot->refreshParameter(FactSystem::defaultComponentId, "SENS_BOARD_ROT"); - // Mag rotation parameters are optional - if (_autopilot->parameterExists("CAL_MAG0_ROT")) { - _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG0_ROT"); - } - if (_autopilot->parameterExists("CAL_MAG1_ROT")) { - _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG1_ROT"); + QString calCompletePrefix("calibration done:"); + if (text.startsWith(calCompletePrefix)) { + _stopCalibration(StopCalibrationSuccess); + return; } - if (_autopilot->parameterExists("CAL_MAG2_ROT")) { - _autopilot->refreshParameter(FactSystem::defaultComponentId, "CAL_MAG2_ROT"); + + if (text.startsWith("calibration cancelled")) { + _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed); + return; } + if (text.startsWith("calibration failed")) { + _stopCalibration(StopCalibrationFailed); + return; + } +} + +void SensorsComponentController::_refreshParams(void) +{ // Pull full set in order to get all cal values back _autopilot->refreshAllParameters(); } @@ -339,18 +412,6 @@ bool SensorsComponentController::fixedWing(void) return uas->getSystemType() == MAV_TYPE_FIXED_WING; } -void SensorsComponentController::_updateAndEmitGyroCalInProgress(bool inProgress) -{ - _gyroCalInProgress = inProgress; - emit gyroCalInProgressChanged(); -} - -void SensorsComponentController::_updateAndEmitShowGyroCalArea(bool show) -{ - _showGyroCalArea = show; - emit showGyroCalAreaChanged(); -} - void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) { _showOrientationCalArea = show; @@ -359,12 +420,15 @@ void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) void SensorsComponentController::_hideAllCalAreas(void) { - _updateAndEmitShowGyroCalArea(false); _updateAndEmitShowOrientationCalArea(false); } -void SensorsComponentController::_updateAndEmitCalInProgressText(const QString& text) +void SensorsComponentController::cancelCalibration(void) { - _calInProgressText = text; - emit calInProgressTextChanged(text); -} + // The firmware doesn't allow us to cancel calibration. The best we can do is wait + // for it to timeout. + _waitingForCancel = true; + emit waitingForCancelChanged(); + _cancelButton->setEnabled(false); + _uas->stopCalibration(); +} \ No newline at end of file diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.h b/src/AutoPilotPlugins/PX4/SensorsComponentController.h index 57bc493f3ac938abcd16fdfdd91d17188ce79e13..dd5c62c7875bf6b322724d87380e70d329e3425c 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.h +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.h @@ -50,18 +50,11 @@ public: Q_PROPERTY(QQuickItem* gyroButton MEMBER _gyroButton) Q_PROPERTY(QQuickItem* accelButton MEMBER _accelButton) Q_PROPERTY(QQuickItem* airspeedButton MEMBER _airspeedButton) + Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton) + Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText) - Q_PROPERTY(bool showCompass0 MEMBER _showCompass0 CONSTANT) - Q_PROPERTY(bool showCompass1 MEMBER _showCompass1 CONSTANT) - Q_PROPERTY(bool showCompass2 MEMBER _showCompass2 CONSTANT) - - Q_PROPERTY(bool showGyroCalArea MEMBER _showGyroCalArea NOTIFY showGyroCalAreaChanged) Q_PROPERTY(bool showOrientationCalArea MEMBER _showOrientationCalArea NOTIFY showOrientationCalAreaChanged) - Q_PROPERTY(bool gyroCalInProgress MEMBER _gyroCalInProgress NOTIFY gyroCalInProgressChanged) - - Q_PROPERTY(QString calInProgressText MEMBER _calInProgressText NOTIFY calInProgressTextChanged) - Q_PROPERTY(bool orientationCalDownSideDone MEMBER _orientationCalDownSideDone NOTIFY orientationCalSidesDoneChanged) Q_PROPERTY(bool orientationCalUpsideDownSideDone MEMBER _orientationCalUpsideDownSideDone NOTIFY orientationCalSidesDoneChanged) Q_PROPERTY(bool orientationCalLeftSideDone MEMBER _orientationCalLeftSideDone NOTIFY orientationCalSidesDoneChanged) @@ -69,6 +62,13 @@ public: Q_PROPERTY(bool orientationCalNoseDownSideDone MEMBER _orientationCalNoseDownSideDone NOTIFY orientationCalSidesDoneChanged) Q_PROPERTY(bool orientationCalTailDownSideDone MEMBER _orientationCalTailDownSideDone NOTIFY orientationCalSidesDoneChanged) + Q_PROPERTY(bool orientationCalDownSideVisible MEMBER _orientationCalDownSideVisible NOTIFY orientationCalSidesVisibleChanged) + Q_PROPERTY(bool orientationCalUpsideDownSideVisible MEMBER _orientationCalUpsideDownSideVisible NOTIFY orientationCalSidesVisibleChanged) + Q_PROPERTY(bool orientationCalLeftSideVisible MEMBER _orientationCalLeftSideVisible NOTIFY orientationCalSidesVisibleChanged) + Q_PROPERTY(bool orientationCalRightSideVisible MEMBER _orientationCalRightSideVisible NOTIFY orientationCalSidesVisibleChanged) + Q_PROPERTY(bool orientationCalNoseDownSideVisible MEMBER _orientationCalNoseDownSideVisible NOTIFY orientationCalSidesVisibleChanged) + Q_PROPERTY(bool orientationCalTailDownSideVisible MEMBER _orientationCalTailDownSideVisible NOTIFY orientationCalSidesVisibleChanged) + Q_PROPERTY(bool orientationCalDownSideInProgress MEMBER _orientationCalDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) Q_PROPERTY(bool orientationCalUpsideDownSideInProgress MEMBER _orientationCalUpsideDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) Q_PROPERTY(bool orientationCalLeftSideInProgress MEMBER _orientationCalLeftSideInProgress NOTIFY orientationCalSidesInProgressChanged) @@ -76,37 +76,48 @@ public: Q_PROPERTY(bool orientationCalNoseDownSideInProgress MEMBER _orientationCalNoseDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) Q_PROPERTY(bool orientationCalTailDownSideInProgress MEMBER _orientationCalTailDownSideInProgress NOTIFY orientationCalSidesInProgressChanged) + Q_PROPERTY(bool orientationCalDownSideRotate MEMBER _orientationCalDownSideRotate NOTIFY orientationCalSidesRotateChanged) + Q_PROPERTY(bool orientationCalLeftSideRotate MEMBER _orientationCalLeftSideRotate NOTIFY orientationCalSidesRotateChanged) + Q_PROPERTY(bool orientationCalNoseDownSideRotate MEMBER _orientationCalNoseDownSideRotate NOTIFY orientationCalSidesRotateChanged) + + Q_PROPERTY(bool waitingForCancel MEMBER _waitingForCancel NOTIFY waitingForCancelChanged) + Q_INVOKABLE void calibrateCompass(void); Q_INVOKABLE void calibrateGyro(void); Q_INVOKABLE void calibrateAccel(void); Q_INVOKABLE void calibrateAirspeed(void); + Q_INVOKABLE void cancelCalibration(void); bool fixedWing(void); signals: void showGyroCalAreaChanged(void); void showOrientationCalAreaChanged(void); - void gyroCalInProgressChanged(void); void orientationCalSidesDoneChanged(void); + void orientationCalSidesVisibleChanged(void); void orientationCalSidesInProgressChanged(void); - void calInProgressTextChanged(const QString& newText); + void orientationCalSidesRotateChanged(void); + void resetStatusTextArea(void); + void waitingForCancelChanged(void); + void setCompassRotations(void); private slots: void _handleUASTextMessage(int uasId, int compId, int severity, QString text); private: - void _startCalibration(void); - void _stopCalibration(bool failed); - void _beginTextLogging(void); + void _startLogCalibration(void); + void _startVisualCalibration(void); void _appendStatusLog(const QString& text); void _refreshParams(void); void _hideAllCalAreas(void); - void _updateAndEmitGyroCalInProgress(bool inProgress); - - void _updateAndEmitCalInProgressText(const QString& text); + enum StopCalibrationCode { + StopCalibrationSuccess, + StopCalibrationFailed, + StopCalibrationCancelled + }; + void _stopCalibration(StopCalibrationCode code); - void _updateAndEmitShowGyroCalArea(bool show); void _updateAndEmitShowOrientationCalArea(bool show); QQuickItem* _statusLog; @@ -115,6 +126,8 @@ private: QQuickItem* _gyroButton; QQuickItem* _accelButton; QQuickItem* _airspeedButton; + QQuickItem* _cancelButton; + QQuickItem* _orientationCalAreaHelpText; bool _showGyroCalArea; bool _showOrientationCalArea; @@ -127,8 +140,6 @@ private: bool _magCalInProgress; bool _accelCalInProgress; - QString _calInProgressText; - bool _orientationCalDownSideDone; bool _orientationCalUpsideDownSideDone; bool _orientationCalLeftSideDone; @@ -136,6 +147,13 @@ private: bool _orientationCalNoseDownSideDone; bool _orientationCalTailDownSideDone; + bool _orientationCalDownSideVisible; + bool _orientationCalUpsideDownSideVisible; + bool _orientationCalLeftSideVisible; + bool _orientationCalRightSideVisible; + bool _orientationCalNoseDownSideVisible; + bool _orientationCalTailDownSideVisible; + bool _orientationCalDownSideInProgress; bool _orientationCalUpsideDownSideInProgress; bool _orientationCalLeftSideInProgress; @@ -143,9 +161,15 @@ private: bool _orientationCalNoseDownSideInProgress; bool _orientationCalTailDownSideInProgress; - bool _textLoggingStarted; + bool _orientationCalDownSideRotate; + bool _orientationCalLeftSideRotate; + bool _orientationCalNoseDownSideRotate; + + bool _unknownFirmwareVersion; + bool _waitingForCancel; AutoPilotPlugin* _autopilot; + UASInterface* _uas; }; #endif diff --git a/src/qgcunittest/MockUAS.h b/src/qgcunittest/MockUAS.h index 0db0c3e14b1c825a0c7fa12ccd0fb4806061084a..d0b7b3087b4bc1bcff1b8acce59344e46cb0364d 100644 --- a/src/qgcunittest/MockUAS.h +++ b/src/qgcunittest/MockUAS.h @@ -105,6 +105,8 @@ public: virtual QString getSystemTypeName() { Q_ASSERT(false); return _bogusString; }; virtual int getAutopilotType() { return MAV_AUTOPILOT_PX4; }; virtual QGCUASFileManager* getFileManager() {Q_ASSERT(false); return NULL; } + virtual void startCalibration(StartCalibrationType calType) { Q_UNUSED(calType); return; }; + virtual void stopCalibration() { return; }; /** @brief Send a message over this link (to this or to all UAS on this link) */ virtual void sendMessage(LinkInterface* link, mavlink_message_t message){ Q_UNUSED(link); Q_UNUSED(message); Q_ASSERT(false); } @@ -152,11 +154,6 @@ public slots: virtual void setLocalPositionSetpoint(float x, float y, float z, float yaw) { Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(z); Q_UNUSED(yaw); Q_ASSERT(false); }; virtual void setLocalPositionOffset(float x, float y, float z, float yaw) { Q_UNUSED(x); Q_UNUSED(y); Q_UNUSED(z); Q_UNUSED(yaw); Q_ASSERT(false); }; - virtual void startRadioControlCalibration(int param) { Q_UNUSED(param); return; }; - virtual void endRadioControlCalibration() { return; }; - virtual void startMagnetometerCalibration() { Q_ASSERT(false); }; - virtual void startGyroscopeCalibration() { Q_ASSERT(false); }; - virtual void startPressureCalibration() { Q_ASSERT(false); }; virtual void setBatterySpecs(const QString& specs) { Q_UNUSED(specs); Q_ASSERT(false); }; virtual QString getBatterySpecs() { Q_ASSERT(false); return _bogusString; }; virtual void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, double lat, double lon, double alt, float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 1b3c0e31cca8468e12e377078ee6b1a378dfae85..ae97ec0186d82459ea3f3715a77422e0b01a98c8 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1439,19 +1439,67 @@ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw) Q_UNUSED(yaw); } -void UAS::startRadioControlCalibration(int param) +void UAS::startCalibration(UASInterface::StartCalibrationType calType) { + int gyroCal = 0; + int magCal = 0; + int airspeedCal = 0; + int radioCal = 0; + int accelCal = 0; + + switch (calType) { + case StartCalibrationGyro: + gyroCal = 1; + break; + case StartCalibrationMag: + magCal = 1; + break; + case StartCalibrationAirspeed: + airspeedCal = 1; + break; + case StartCalibrationRadio: + radioCal = 1; + break; + case StartCalibrationAccel: + accelCal = 1; + break; + } + mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, param, 0, 0, 0); + mavlink_msg_command_long_pack(mavlink->getSystemId(), + mavlink->getComponentId(), + &msg, + uasId, + 0, // target component + MAV_CMD_PREFLIGHT_CALIBRATION, // command id + 0, // 0=first transmission of command + gyroCal, // gyro cal + magCal, // mag cal + 0, // ground pressure + radioCal, // radio cal + accelCal, // accel cal + airspeedCal, // airspeed cal + 0); // unused sendMessage(msg); } -void UAS::endRadioControlCalibration() +void UAS::stopCalibration(void) { mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 0, 0, 0, 0); + mavlink_msg_command_long_pack(mavlink->getSystemId(), + mavlink->getComponentId(), + &msg, + uasId, + 0, // target component + MAV_CMD_PREFLIGHT_CALIBRATION, // command id + 0, // 0=first transmission of command + 0, // gyro cal + 0, // mag cal + 0, // ground pressure + 0, // radio cal + 0, // accel cal + 0, // airspeed cal + 0); // unused sendMessage(msg); } @@ -1469,30 +1517,6 @@ void UAS::stopDataRecording() sendMessage(msg); } -void UAS::startMagnetometerCalibration() -{ - mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 1, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -void UAS::startGyroscopeCalibration() -{ - mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1, 0, 0, 0, 0, 0, 0); - sendMessage(msg); -} - -void UAS::startPressureCalibration() -{ - mavlink_message_t msg; - // Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio - mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 1, 0, 0, 0, 0); - sendMessage(msg); -} - /** * Check if time is smaller than 40 years, assuming no system without Unix * timestamp runs longer than 40 years continuously without reboot. In worst case diff --git a/src/uas/UAS.h b/src/uas/UAS.h index fadb9b2867537ebef5e7c81672f873d437d80e7b..3a689d033a48a754a31ad1e458491fc7ca833acc 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -863,11 +863,8 @@ public slots: /** @brief Add an offset in body frame to the setpoint */ void setLocalPositionOffset(float x, float y, float z, float yaw); - void startRadioControlCalibration(int param=1); - void endRadioControlCalibration(); - void startMagnetometerCalibration(); - void startGyroscopeCalibration(); - void startPressureCalibration(); + void startCalibration(StartCalibrationType calType); + void stopCalibration(void); void startDataRecording(); void stopDataRecording(); diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 4d0c34bce0fe5c5e5bcef8f740b9943cda19146c..6a69e5423dd88bbdd06ad376c6c794e72d3ad58c 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -242,6 +242,20 @@ public: static const unsigned int WAYPOINT_RADIUS_DEFAULT_FIXED_WING = 25; static const unsigned int WAYPOINT_RADIUS_DEFAULT_ROTARY_WING = 5; + + enum StartCalibrationType { + StartCalibrationRadio, + StartCalibrationGyro, + StartCalibrationMag, + StartCalibrationAirspeed, + StartCalibrationAccel + }; + + /// Starts the specified calibration + virtual void startCalibration(StartCalibrationType calType) = 0; + + /// Ends any current calibration + virtual void stopCalibration(void) = 0; public slots: @@ -344,12 +358,6 @@ public slots: virtual void setLocalPositionSetpoint(float x, float y, float z, float yaw) = 0; virtual void setLocalPositionOffset(float x, float y, float z, float yaw) = 0; - virtual void startRadioControlCalibration(int param=1) = 0; - virtual void endRadioControlCalibration() = 0; - virtual void startMagnetometerCalibration() = 0; - virtual void startGyroscopeCalibration() = 0; - virtual void startPressureCalibration() = 0; - /** @brief Return if this a rotary wing */ virtual bool isRotaryWing() = 0; /** @brief Return if this is a fixed wing */ diff --git a/src/ui/px4_configuration/PX4RCCalibration.cc b/src/ui/px4_configuration/PX4RCCalibration.cc index 6d9302b0f619c3b77b194fefe3cccf6c367ad78b..9bf76c54bad71451bf9cf73bb0afad9e723e28c0 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.cc +++ b/src/ui/px4_configuration/PX4RCCalibration.cc @@ -892,7 +892,7 @@ void PX4RCCalibration::_writeCalibration(void) { if (!_mav) return; - _mav->endRadioControlCalibration(); + _mav->stopCalibration(); _validateCalibration(); @@ -986,7 +986,7 @@ void PX4RCCalibration::_startCalibration(void) _resetInternalCalibrationValues(); // Let the mav known we are starting calibration. This should turn off motors and so forth. - _mav->startRadioControlCalibration(); + _mav->startCalibration(UASInterface::StartCalibrationRadio); _ui->rcCalNext->setText(tr("Next")); _ui->rcCalCancel->setEnabled(true); @@ -1001,7 +1001,7 @@ void PX4RCCalibration::_stopCalibration(void) _currentStep = -1; if (_mav) { - _mav->endRadioControlCalibration(); + _mav->stopCalibration(); _setInternalCalibrationValuesFromParameters(); } else { _resetInternalCalibrationValues();