diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml index a4d83794a2f2ec70639347d9a27aadc3bec79348..10957b5067c4267265124f4ebdc0a84d43da1524 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml @@ -27,20 +27,17 @@ QGCView { // Help text which is shown both in the status text area prior to pressing a cal button and in the // pre-calibration dialog. - readonly property string orientationHelp: "If the orientation is in the direction of flight, select None." - readonly property string boardRotationText: "If the autopilot is mounted in flight direction, leave the default value (None)" + readonly property string orientationHelpSet: "If the orientation is in the direction of flight, select None." + readonly property string orientationHelpCal: "Before calibrating make sure orientation settings are correct. " + orientationHelpSet readonly property string compassRotationText: "If the compass or GPS module is mounted in flight direction, leave the default value (None)" - readonly property string compassHelp: "For Compass calibration you will need to rotate your vehicle through a number of positions. Most users prefer to do this wirelessly with the telemetry link." + readonly property string compassHelp: "For Compass calibration you will need to rotate your vehicle through a number of positions." readonly property string gyroHelp: "For Gyroscope calibration you will need to place your vehicle on a surface and leave it still." readonly property string accelHelp: "For Accelerometer calibration you will need to place your vehicle on all six sides on a perfectly level surface and hold it still in each orientation for a few seconds." readonly property string levelHelp: "To level the horizon you need to place the vehicle in its level flight position and press OK." readonly property string airspeedHelp: "For Airspeed calibration you will need to keep your airspeed sensor out of any wind and then blow across the sensor." - readonly property string statusTextAreaDefaultText: "Start the individual calibration steps by clicking one of the buttons above." - - // Used to pass what type of calibration is being performed to the preCalibrationDialog - property string preCalibrationDialogType + readonly property string statusTextAreaDefaultText: "Start the individual calibration steps by clicking one of the buttons to the left." // Used to pass help text to the preCalibrationDialog dialog property string preCalibrationDialogHelp @@ -100,6 +97,14 @@ QGCView { property bool showCompass2Rot: compass2Id.value > 0 && compass2External && compass2Use property bool showCompass3Rot: compass3Id.value > 0 && compass3External && compass3Use + readonly property int _calTypeCompass: 1 ///< Calibrate compass + readonly property int _calTypeAccel: 2 ///< Calibrate accel + readonly property int _calTypeSet: 3 ///< Set orientations only + + property bool _orientationsDialogShowCompass: true + property string _orientationDialogHelp: orientationHelpSet + property int _orientationDialogCalType + function validCompassOffsets(compassParamPrefix) { var ofsX = controller.getParameterFact(-1, compassParamPrefix + "X") var ofsY = controller.getParameterFact(-1, compassParamPrefix + "Y") @@ -107,6 +112,34 @@ QGCView { return Math.sqrt(ofsX.value^2 + ofsY.value^2 + ofsZ.value^2) < 600 } + function showOrientationsDialog(calType) { + var dialogTitle + var buttons = StandardButton.Ok + + _orientationDialogCalType = calType + switch (calType) { + case _calTypeCompass: + _orientationsDialogShowCompass = true + _orientationDialogHelp = orientationHelpCal + dialogTitle = qsTr("Calibrate Compass") + buttons |= StandardButton.Cancel + break + case _calTypeAccel: + _orientationsDialogShowCompass = false + _orientationDialogHelp = orientationHelpCal + dialogTitle = qsTr("Calibrate Accelerometer") + buttons |= StandardButton.Cancel + break + case _calTypeSet: + _orientationsDialogShowCompass = true + _orientationDialogHelp = orientationHelpSet + dialogTitle = qsTr("SetOrientations") + break + } + + showDialog(orientationsDialogComponent, dialogTitle, qgcView.showDialogDefaultWidth, buttons) + } + APMSensorsComponentController { id: controller factPanel: panel @@ -116,6 +149,7 @@ QGCView { accelButton: accelButton nextButton: nextButton cancelButton: cancelButton + setOrientationsButton: setOrientationsButton orientationCalAreaHelpText: orientationCalAreaHelpText onResetStatusTextArea: statusLog.text = statusTextAreaDefaultText @@ -129,7 +163,7 @@ QGCView { } onCalibrationComplete: { - if (preCalibrationDialogType == "accel") { + if (_orientationDialogCalType == _calTypeAccel) { _postCalibrationDialogText = qsTr("Accelerometer calibration complete.") _postCalibrationDialogParams = [ "INS_ACCSCAL_X", "INS_ACCSCAL_Y", "INS_ACCSCAL_Z", "INS_ACC2SCAL_X", "INS_ACC2SCAL_Y", "INS_ACC2SCAL_Z", @@ -137,7 +171,7 @@ QGCView { "INS_GYROFFS_X", "INS_GYROFFS_Y", "INS_GYROFFS_Z", "INS_GYR2OFFS_X", "INS_GYR2OFFS_Y", "INS_GYR2OFFS_Z", "INS_GYR3OFFS_X", "INS_GYR3OFFS_Y", "INS_GYR3OFFS_Z" ] - } else if (preCalibrationDialogType == "compass") { + } else if (_orientationDialogCalType == _calTypeCompass) { _postCalibrationDialogText = qsTr("Compass calibration complete. ") _postCalibrationDialogParams = []; if (compass1Id.value > 0) { @@ -179,42 +213,6 @@ QGCView { QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } - Component { - id: preCalibrationDialogComponent - - QGCViewDialog { - id: preCalibrationDialog - - function accept() { - if (preCalibrationDialogType == "accel") { - controller.calibrateAccel() - } else if (preCalibrationDialogType == "compass") { - controller.calibrateCompass() - } - preCalibrationDialog.hideDialog() - } - - QGCLabel { - id: label - anchors.left: parent.left - anchors.right: parent.right - wrapMode: Text.WordWrap - text: qsTr("Before calibrating make sure orientation settings are correct.") - } - - Loader { - id: rotationsLoader - anchors.topMargin: ScreenTools.defaultFontPixelHeight - anchors.top: label.bottom - anchors.left: parent.left - anchors.right: parent.right - sourceComponent: rotationCombosComponent - - property bool showCompassRotations: preCalibrationDialogType == "accel" ? false : true - } - } - } - Component { id: postCalibrationDialogComponent @@ -260,121 +258,146 @@ QGCView { } Component { - id: rotationCombosComponent + id: orientationsDialogComponent - Column { - QGCLabel { - font.pointSize: sideBarH1PointSize - text: qsTr("Set Orientations") - } + QGCViewDialog { + id: orientationsDialog - Item { - width: 1 - height: ScreenTools.defaultFontPixelHeight + function accept() { + if (_orientationDialogCalType == _calTypeAccel) { + controller.calibrateAccel() + } else if (_orientationDialogCalType == _calTypeCompass) { + controller.calibrateCompass() + } + orientationsDialog.hideDialog() } - QGCLabel { - width: parent.width - wrapMode: Text.WordWrap - text: orientationHelp - } + QGCFlickable { + anchors.fill: parent + contentHeight: columnLayout.height + clip: true - Item { - width: 1 - height: ScreenTools.defaultFontPixelHeight - } + Column { + id: columnLayout + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.left: parent.left + anchors.right: parent.right + anchors.top: parent.top + spacing: ScreenTools.defaultFontPixelHeight - // Board rotation - QGCLabel { - text: qsTr("Autopilot Orientation") - } + QGCLabel { + width: parent.width + wrapMode: Text.WordWrap + text: _orientationDialogHelp + } - FactComboBox { - id: boardRotationCombo - width: parent.width - fact: boardRot - indexModel: false - } + Column { + QGCLabel { + text: qsTr("Autopilot Orientation:") + } - Item { - width: 1 - height: ScreenTools.defaultFontPixelHeight - } + FactComboBox { + width: rotationColumnWidth + indexModel: false + fact: boardRot + } + } - // Compass 1 rotation - QGCLabel { - text: qsTr("Compass 1 Orientation") - visible: showCompassRotations && showCompass1Rot - } + Column { + visible: _orientationsDialogShowCompass - FactComboBox { - width: parent.width - fact: compass1Rot - indexModel: false - visible: showCompassRotations && showCompass1Rot - } + Component { + id: compass1ComponentLabel - Item { - width: 1 - height: ScreenTools.defaultFontPixelHeight - } + QGCLabel { + text: qsTr("Compass 1 Orientation:") + } + } - // Compass 2 rotation - QGCLabel { - text: qsTr("Compass 2 Orientation") - visible: showCompassRotations && showCompass2Rot - } + Component { + id: compass1ComponentCombo - FactComboBox { - width: parent.width - fact: compass2Rot - indexModel: false - visible: showCompassRotations && showCompass2Rot - } + FactComboBox { + width: rotationColumnWidth + indexModel: false + fact: compass1Rot + } + } - Item { - width: 1 - height: ScreenTools.defaultFontPixelHeight - } + Loader { sourceComponent: showCompass1Rot ? compass1ComponentLabel : null } + Loader { sourceComponent: showCompass1Rot ? compass1ComponentCombo : null } + } - // Compass 3 rotation - QGCLabel { - text: qsTr("Compass 3 Orientation") - visible: showCompassRotations && showCompass3Rot - } + Column { + visible: _orientationsDialogShowCompass - FactComboBox { - width: parent.width - fact: compass3Rot - indexModel: false - visible: showCompassRotations && showCompass3Rot - } - } // Column - } // Component - Rotation combos + Component { + id: compass2ComponentLabel + + QGCLabel { + text: qsTr("Compass 2 Orientation:") + } + } + + Component { + id: compass2ComponentCombo + + FactComboBox { + width: rotationColumnWidth + indexModel: false + fact: compass2Rot + } + } + + Loader { sourceComponent: showCompass2Rot ? compass2ComponentLabel : null } + Loader { sourceComponent: showCompass2Rot ? compass2ComponentCombo : null } + } + + Column { + visible: _orientationsDialogShowCompass + + Component { + id: compass3ComponentLabel + + QGCLabel { + text: qsTr("Compass 3 Orientation") + } + } + + Component { + id: compass3ComponentCombo + + FactComboBox { + width: rotationColumnWidth + indexModel: false + fact: compass3Rot + } + } + Loader { sourceComponent: showCompass3Rot ? compass3ComponentLabel : null } + Loader { sourceComponent: showCompass3Rot ? compass3ComponentCombo : null } + } + } // Column + } // QGCFlickable + } // QGCViewDialog + } // Component - orientationsDialogComponent QGCViewPanel { id: panel anchors.fill: parent - Row { - id: buttonsRow - spacing: ScreenTools.defaultFontPixelWidth + Column { + id: buttonColumn + spacing: ScreenTools.defaultFontPixelHeight / 2 readonly property int buttonWidth: ScreenTools.defaultFontPixelWidth * 15 - QGCLabel { text: qsTr("Calibrate:"); anchors.baseline: compassButton.baseline } - IndicatorButton { id: accelButton width: parent.buttonWidth text: qsTr("Accelerometer") indicatorGreen: !accelCalNeeded - onClicked: { - preCalibrationDialogType = "accel" - preCalibrationDialogHelp = accelHelp - showDialog(preCalibrationDialogComponent, qsTr("Calibrate Accelerometer"), qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) - } + onClicked: showOrientationsDialog(_calTypeAccel) } IndicatorButton { @@ -387,15 +410,14 @@ QGCView { if (controller.accelSetupNeeded) { showMessage(qsTr("Calibrate Compass"), qsTr("Accelerometer must be calibrated prior to Compass."), StandardButton.Ok) } else { - preCalibrationDialogType = "compass" - preCalibrationDialogHelp = compassHelp - showDialog(preCalibrationDialogComponent, qsTr("Calibrate Compass"), qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) + showOrientationsDialog(_calTypeCompass) } } } QGCButton { id: nextButton + width: parent.buttonWidth text: qsTr("Next") enabled: false onClicked: controller.nextClicked() @@ -403,136 +425,137 @@ QGCView { QGCButton { id: cancelButton + width: parent.buttonWidth text: qsTr("Cancel") enabled: false onClicked: controller.cancelCalibration() } - } // Row - Cal buttons - - ProgressBar { - id: progressBar - anchors.topMargin: ScreenTools.defaultFontPixelHeight - anchors.top: buttonsRow.bottom - anchors.left: parent.left - anchors.right: centerPanel.right - } - Item { - id: centerPanel - anchors.topMargin: ScreenTools.defaultFontPixelHeight - anchors.rightMargin: ScreenTools.defaultFontPixelHeight - anchors.top: progressBar.bottom - anchors.bottom: parent.bottom - anchors.left: parent.left - anchors.right: rotationsLoader.left - - TextArea { - id: statusTextArea - anchors.fill: parent - readOnly: true - frameVisible: false - text: statusTextAreaDefaultText + QGCButton { + id: setOrientationsButton + width: parent.buttonWidth + text: qsTr("Set Orientations") + onClicked: showOrientationsDialog(_calTypeSet) + } + } // Column - Buttons - style: TextAreaStyle { - textColor: qgcPal.text - backgroundColor: qgcPal.windowShade - } + Column { + anchors.leftMargin: ScreenTools.defaultFontPixelWidth / 2 + anchors.left: buttonColumn.right + anchors.right: parent.right + anchors.top: parent.top + anchors.bottom: parent.bottom + + ProgressBar { + id: progressBar + anchors.left: parent.left + anchors.right: parent.right } - Rectangle { - id: orientationCalArea - anchors.fill: parent - visible: controller.showOrientationCalArea - color: qgcPal.windowShade + Item { height: ScreenTools.defaultFontPixelHeight; width: 10 } // spacer - QGCLabel { - id: orientationCalAreaHelpText - anchors.margins: ScreenTools.defaultFontPixelWidth - anchors.top: orientationCalArea.top - anchors.left: orientationCalArea.left - width: parent.width - wrapMode: Text.WordWrap - font.pointSize: ScreenTools.mediumFontPointSize + Item { + id: centerPanel + width: parent.width + height: parent.height - y + + TextArea { + id: statusTextArea + anchors.fill: parent + readOnly: true + frameVisible: false + text: statusTextAreaDefaultText + + style: TextAreaStyle { + textColor: qgcPal.text + backgroundColor: qgcPal.windowShade + } } - Flow { - anchors.topMargin: ScreenTools.defaultFontPixelWidth - anchors.top: orientationCalAreaHelpText.bottom - anchors.bottom: parent.bottom - anchors.left: parent.left - anchors.right: parent.right - spacing: ScreenTools.defaultFontPixelWidth - - property real indicatorWidth: (width / 3) - (spacing * 2) - property real indicatorHeight: (height / 2) - spacing - - VehicleRotationCal { - width: parent.indicatorWidth - height: parent.indicatorHeight - visible: controller.orientationCalDownSideVisible - calValid: controller.orientationCalDownSideDone - calInProgress: controller.orientationCalDownSideInProgress - calInProgressText: controller.orientationCalDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalDownSideRotate ? "qrc:///qmlimages/VehicleDownRotate.png" : "qrc:///qmlimages/VehicleDown.png" - } - VehicleRotationCal { - width: parent.indicatorWidth - height: parent.indicatorHeight - visible: controller.orientationCalUpsideDownSideVisible - calValid: controller.orientationCalUpsideDownSideDone - calInProgress: controller.orientationCalUpsideDownSideInProgress - calInProgressText: controller.orientationCalUpsideDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalUpsideDownSideRotate ? "qrc:///qmlimages/VehicleUpsideDownRotate.png" : "qrc:///qmlimages/VehicleUpsideDown.png" - } - VehicleRotationCal { - width: parent.indicatorWidth - height: parent.indicatorHeight - visible: controller.orientationCalNoseDownSideVisible - calValid: controller.orientationCalNoseDownSideDone - calInProgress: controller.orientationCalNoseDownSideInProgress - calInProgressText: controller.orientationCalNoseDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalNoseDownSideRotate ? "qrc:///qmlimages/VehicleNoseDownRotate.png" : "qrc:///qmlimages/VehicleNoseDown.png" + Rectangle { + id: orientationCalArea + anchors.fill: parent + visible: controller.showOrientationCalArea + color: qgcPal.windowShade + + QGCLabel { + id: orientationCalAreaHelpText + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.top: orientationCalArea.top + anchors.left: orientationCalArea.left + width: parent.width + wrapMode: Text.WordWrap + font.pointSize: ScreenTools.mediumFontPointSize } - VehicleRotationCal { - width: parent.indicatorWidth - height: parent.indicatorHeight - visible: controller.orientationCalTailDownSideVisible - calValid: controller.orientationCalTailDownSideDone - calInProgress: controller.orientationCalTailDownSideInProgress - calInProgressText: controller.orientationCalTailDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalTailDownSideRotate ? "qrc:///qmlimages/VehicleTailDownRotate.png" : "qrc:///qmlimages/VehicleTailDown.png" - } - VehicleRotationCal { - width: parent.indicatorWidth - height: parent.indicatorHeight - visible: controller.orientationCalLeftSideVisible - calValid: controller.orientationCalLeftSideDone - calInProgress: controller.orientationCalLeftSideInProgress - calInProgressText: controller.orientationCalLeftSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalLeftSideRotate ? "qrc:///qmlimages/VehicleLeftRotate.png" : "qrc:///qmlimages/VehicleLeft.png" - } - VehicleRotationCal { - width: parent.indicatorWidth - height: parent.indicatorHeight - visible: controller.orientationCalRightSideVisible - calValid: controller.orientationCalRightSideDone - calInProgress: controller.orientationCalRightSideInProgress - calInProgressText: controller.orientationCalRightSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalRightSideRotate ? "qrc:///qmlimages/VehicleRightRotate.png" : "qrc:///qmlimages/VehicleRight.png" + + Flow { + anchors.topMargin: ScreenTools.defaultFontPixelWidth + anchors.top: orientationCalAreaHelpText.bottom + anchors.bottom: parent.bottom + anchors.left: parent.left + anchors.right: parent.right + spacing: ScreenTools.defaultFontPixelWidth + + property real indicatorWidth: (width / 3) - (spacing * 2) + property real indicatorHeight: (height / 2) - spacing + + VehicleRotationCal { + width: parent.indicatorWidth + height: parent.indicatorHeight + visible: controller.orientationCalDownSideVisible + calValid: controller.orientationCalDownSideDone + calInProgress: controller.orientationCalDownSideInProgress + calInProgressText: controller.orientationCalDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: controller.orientationCalDownSideRotate ? "qrc:///qmlimages/VehicleDownRotate.png" : "qrc:///qmlimages/VehicleDown.png" + } + VehicleRotationCal { + width: parent.indicatorWidth + height: parent.indicatorHeight + visible: controller.orientationCalUpsideDownSideVisible + calValid: controller.orientationCalUpsideDownSideDone + calInProgress: controller.orientationCalUpsideDownSideInProgress + calInProgressText: controller.orientationCalUpsideDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: controller.orientationCalUpsideDownSideRotate ? "qrc:///qmlimages/VehicleUpsideDownRotate.png" : "qrc:///qmlimages/VehicleUpsideDown.png" + } + VehicleRotationCal { + width: parent.indicatorWidth + height: parent.indicatorHeight + visible: controller.orientationCalNoseDownSideVisible + calValid: controller.orientationCalNoseDownSideDone + calInProgress: controller.orientationCalNoseDownSideInProgress + calInProgressText: controller.orientationCalNoseDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: controller.orientationCalNoseDownSideRotate ? "qrc:///qmlimages/VehicleNoseDownRotate.png" : "qrc:///qmlimages/VehicleNoseDown.png" + } + VehicleRotationCal { + width: parent.indicatorWidth + height: parent.indicatorHeight + visible: controller.orientationCalTailDownSideVisible + calValid: controller.orientationCalTailDownSideDone + calInProgress: controller.orientationCalTailDownSideInProgress + calInProgressText: controller.orientationCalTailDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: controller.orientationCalTailDownSideRotate ? "qrc:///qmlimages/VehicleTailDownRotate.png" : "qrc:///qmlimages/VehicleTailDown.png" + } + VehicleRotationCal { + width: parent.indicatorWidth + height: parent.indicatorHeight + visible: controller.orientationCalLeftSideVisible + calValid: controller.orientationCalLeftSideDone + calInProgress: controller.orientationCalLeftSideInProgress + calInProgressText: controller.orientationCalLeftSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: controller.orientationCalLeftSideRotate ? "qrc:///qmlimages/VehicleLeftRotate.png" : "qrc:///qmlimages/VehicleLeft.png" + } + VehicleRotationCal { + width: parent.indicatorWidth + height: parent.indicatorHeight + visible: controller.orientationCalRightSideVisible + calValid: controller.orientationCalRightSideDone + calInProgress: controller.orientationCalRightSideInProgress + calInProgressText: controller.orientationCalRightSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: controller.orientationCalRightSideRotate ? "qrc:///qmlimages/VehicleRightRotate.png" : "qrc:///qmlimages/VehicleRight.png" + } } } - } - } // Item - Cal display area - - Loader { - id: rotationsLoader - anchors.top: centerPanel.top - anchors.bottom: parent.bottom - anchors.right: parent.right - width: rotationColumnWidth - sourceComponent: rotationCombosComponent - - property bool showCompassRotations: true - } + } // Item - Cal display area + } // Column - cal display } // QGCViewPanel } // QGCView diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index 1dbcd76251b2c5898571a65d2e26ee58ef3d5e39..0ac06265e17afd3e7e4764d32e56166867dda5c3 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -26,6 +26,7 @@ APMSensorsComponentController::APMSensorsComponentController(void) : _accelButton(NULL), _nextButton(NULL), _cancelButton(NULL), + _setOrientationsButton(NULL), _showOrientationCalArea(false), _magCalInProgress(false), _accelCalInProgress(false), @@ -85,6 +86,7 @@ void APMSensorsComponentController::_startLogCalibration(void) _compassButton->setEnabled(false); _accelButton->setEnabled(false); + _setOrientationsButton->setEnabled(false); if (_accelCalInProgress) { _nextButton->setEnabled(true); } @@ -95,6 +97,7 @@ void APMSensorsComponentController::_startVisualCalibration(void) { _compassButton->setEnabled(false); _accelButton->setEnabled(false); + _setOrientationsButton->setEnabled(false); _cancelButton->setEnabled(true); _resetInternalState(); @@ -138,6 +141,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll _compassButton->setEnabled(true); _accelButton->setEnabled(true); + _setOrientationsButton->setEnabled(true); _nextButton->setEnabled(false); _cancelButton->setEnabled(false); diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.h b/src/AutoPilotPlugins/APM/APMSensorsComponentController.h index 6ba4dd2c2ca8a57499bdca777b2bc09e109d8d14..5a91ee3b9803c2d3ae6f3184d314d6b17c2386d3 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.h +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.h @@ -36,6 +36,7 @@ public: Q_PROPERTY(QQuickItem* accelButton MEMBER _accelButton) Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton) Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton) + Q_PROPERTY(QQuickItem* setOrientationsButton MEMBER _setOrientationsButton) Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText) Q_PROPERTY(bool compassSetupNeeded READ compassSetupNeeded NOTIFY setupNeededChanged) @@ -123,6 +124,7 @@ private: QQuickItem* _accelButton; QQuickItem* _nextButton; QQuickItem* _cancelButton; + QQuickItem* _setOrientationsButton; QQuickItem* _orientationCalAreaHelpText; bool _showOrientationCalArea; diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.qml b/src/AutoPilotPlugins/PX4/SensorsComponent.qml index 5395afb86f0dc6911545848f21c92248120933d2..1d9a982fff0df18d3a7f39cc94ff21bd75ec3038 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.qml +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.qml @@ -108,6 +108,7 @@ QGCView { airspeedButton: airspeedButton levelButton: levelButton cancelButton: cancelButton + setOrientationsButton: setOrientationsButton orientationCalAreaHelpText: orientationCalAreaHelpText onResetStatusTextArea: statusLog.text = statusTextAreaDefaultText @@ -398,6 +399,7 @@ QGCView { } QGCButton { + id: setOrientationsButton width: parent.buttonWidth text: qsTr("Set Orientations") onClicked: showDialog(setOrientationsDialogComponent, qsTr("Set Orientations"), qgcView.showDialogDefaultWidth, StandardButton.Ok) diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index 9cbb25003a4d75016c5892b8ca46d7db8f0868a4..f3b030055141ce82b18da591964ecf203a944523 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -30,6 +30,7 @@ SensorsComponentController::SensorsComponentController(void) : _airspeedButton(NULL), _levelButton(NULL), _cancelButton(NULL), + _setOrientationsButton(NULL), _showOrientationCalArea(false), _gyroCalInProgress(false), _magCalInProgress(false), @@ -98,6 +99,7 @@ void SensorsComponentController::_startVisualCalibration(void) _accelButton->setEnabled(false); _airspeedButton->setEnabled(false); _levelButton->setEnabled(false); + _setOrientationsButton->setEnabled(false); _cancelButton->setEnabled(true); _resetInternalState(); @@ -140,6 +142,7 @@ void SensorsComponentController::_stopCalibration(SensorsComponentController::St _accelButton->setEnabled(true); _airspeedButton->setEnabled(true); _levelButton->setEnabled(true); + _setOrientationsButton->setEnabled(true); _cancelButton->setEnabled(false); if (code == StopCalibrationSuccess) { diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.h b/src/AutoPilotPlugins/PX4/SensorsComponentController.h index e06b6b6e86201d14f65051a03975fe53be07ae1b..d2818a4d674af53d4315dc9f072b416987aabfb5 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.h +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.h @@ -40,6 +40,7 @@ public: Q_PROPERTY(QQuickItem* airspeedButton MEMBER _airspeedButton) Q_PROPERTY(QQuickItem* levelButton MEMBER _levelButton) Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton) + Q_PROPERTY(QQuickItem* setOrientationsButton MEMBER _setOrientationsButton) Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText) Q_PROPERTY(bool showOrientationCalArea MEMBER _showOrientationCalArea NOTIFY showOrientationCalAreaChanged) @@ -121,6 +122,7 @@ private: QQuickItem* _airspeedButton; QQuickItem* _levelButton; QQuickItem* _cancelButton; + QQuickItem* _setOrientationsButton; QQuickItem* _orientationCalAreaHelpText; bool _showGyroCalArea; diff --git a/src/FactSystem/FactControls/FactTextField.qml b/src/FactSystem/FactControls/FactTextField.qml index d4c31a8f4825064d234ab8eb36a66aa041a3f0df..66b0532a347b7000d10ea2c06880921b085f25b1 100644 --- a/src/FactSystem/FactControls/FactTextField.qml +++ b/src/FactSystem/FactControls/FactTextField.qml @@ -21,7 +21,7 @@ QGCTextField { // At this point all Facts are numeric validator: DoubleValidator {} inputMethodHints: ScreenTools.isiOS ? - Qt.ImhNone : // iOS numeric keyboard has not done button, we can't use eit + Qt.ImhNone : // iOS numeric keyboard has not done button, we can't use it Qt.ImhFormattedNumbersOnly // Forces use of virtual numeric keyboard onEditingFinished: {