7import QGroundControl.FactControls
8import QGroundControl.Controls
12 pageComponent: sensorsPageComponent
15 id: sensorsPageComponent
19 height: availableHeight
21 // Help text which is shown both in the status text area prior to pressing a cal button and in the
22 // pre-calibration dialog.
24 readonly property string orientationHelpSet: qsTr("If mounted in the direction of flight, select None.")
25 readonly property string orientationHelpCal: qsTr("Before calibrating make sure rotation settings are correct. ") + orientationHelpSet
26 readonly property string compassRotationText: qsTr("If the compass or GPS module is mounted in flight direction, leave the default value (None)")
28 readonly property string compassHelp: qsTr("For Compass calibration you will need to rotate your vehicle through a number of positions.")
29 readonly property string gyroHelp: qsTr("For Gyroscope calibration you will need to place your vehicle on a surface and leave it still.")
30 readonly property string accelHelp: qsTr("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.")
31 readonly property string levelHelp: qsTr("To level the horizon you need to place the vehicle in its level flight position and press OK.")
33 readonly property string statusTextAreaDefaultText: qsTr("Start the individual calibration steps by clicking one of the buttons to the left.")
35 // Used to pass help text to the preCalibrationDialog dialog
36 property string preCalibrationDialogHelp
38 property string _postCalibrationDialogText
39 property var _postCalibrationDialogParams
41 readonly property string _badCompassCalText: qsTr("The calibration for Compass %1 appears to be poor. ") +
42 qsTr("Check the compass position within your vehicle and re-do the calibration.")
44 readonly property int sideBarH1PointSize: ScreenTools.mediumFontPointSize
45 readonly property int mainTextH1PointSize: ScreenTools.mediumFontPointSize // Seems to be unused
47 readonly property int rotationColumnWidth: 250
49 property Fact noFact: Fact { }
51 property bool accelCalNeeded: controller.accelSetupNeeded
52 property bool compassCalNeeded: controller.compassSetupNeeded
54 property Fact boardRot: controller.getParameterFact(-1, "AHRS_ORIENTATION")
56 readonly property int _calTypeCompass: 1 ///< Calibrate compass
57 readonly property int _calTypeAccel: 2 ///< Calibrate accel
58 readonly property int _calTypeSet: 3 ///< Set orientations only
59 readonly property int _buttonWidth: ScreenTools.defaultFontPixelWidth * 15
61 property bool _orientationsDialogShowCompass: true
62 property string _orientationDialogHelp: orientationHelpSet
63 property int _orientationDialogCalType
64 property real _margins: ScreenTools.defaultFontPixelHeight / 2
65 property bool _compassAutoRotAvailable: controller.parameterExists(-1, "COMPASS_AUTO_ROT")
66 property Fact _compassAutoRotFact: controller.getParameterFact(-1, "COMPASS_AUTO_ROT", false /* reportMissing */)
67 property bool _compassAutoRot: _compassAutoRotAvailable ? _compassAutoRotFact.rawValue == 2 : false
68 property bool _showSimpleAccelCalOption: false
69 property bool _doSimpleAccelCal: false
70 property var _gcsPosition: QGroundControl.qgcPositionManger.gcsPosition
71 property var _mapPosition: QGroundControl.flightMapPosition
73 function showOrientationsDialog(calType) {
75 var dialogButtons = Dialog.Ok
76 _showSimpleAccelCalOption = false
78 _orientationDialogCalType = calType
81 _orientationsDialogShowCompass = true
82 _orientationDialogHelp = orientationHelpCal
83 dialogTitle = qsTr("Calibrate Compass")
84 dialogButtons |= Dialog.Cancel
87 _orientationsDialogShowCompass = false
88 _orientationDialogHelp = orientationHelpCal
89 dialogTitle = qsTr("Calibrate Accelerometer")
90 dialogButtons |= Dialog.Cancel
93 _orientationsDialogShowCompass = true
94 _orientationDialogHelp = orientationHelpSet
95 dialogTitle = qsTr("Sensor Settings")
99 orientationsDialogFactory.open({ title: dialogTitle, buttons: dialogButtons })
102 function showSimpleAccelCalOption() {
103 _showSimpleAccelCalOption = true
106 function compassLabel(index) {
107 var label = qsTr("Compass %1 ").arg(index+1)
108 var addOpenParan = true
110 if (sensorParams.compassPrimaryFactAvailable) {
111 label += sensorParams.rgCompassPrimary[index] ? qsTr("(primary") : qsTr("(secondary")
115 if (sensorParams.rgCompassExternalParamAvailable[index]) {
122 label += sensorParams.rgCompassExternal[index] ? qsTr("external") : qsTr("internal")
130 factPanelController: controller
133 APMSensorsComponentController {
135 statusLog: statusTextArea
136 progressBar: progressBar
137 nextButton: nextButton
138 cancelButton: cancelButton
139 orientationCalAreaHelpText: orientationCalAreaHelpText
141 property var rgCompassCalFitness: [ controller.compass1CalFitness, controller.compass2CalFitness, controller.compass3CalFitness ]
143 onResetStatusTextArea: statusLog.text = statusTextAreaDefaultText
145 onWaitingForCancelChanged: {
146 if (controller.waitingForCancel) {
147 waitForCancelDialogFactory.open()
151 onCalibrationComplete: {
153 case MAVLink.CalibrationAccel:
154 case MAVLink.CalibrationMag:
155 _singleCompassSettingsComponentShowPriority = true
156 postOnboardCompassCalibrationFactory.open()
161 onSetAllCalButtonsEnabled: {
162 buttonColumn.enabled = enabled
166 QGCPalette { id: qgcPal; colorGroupEnabled: true }
168 QGCPopupDialogFactory {
169 id: waitForCancelDialogFactory
171 dialogComponent: waitForCancelDialogComponent
175 id: waitForCancelDialogComponent
177 QGCSimpleMessageDialog {
178 title: qsTr("Calibration Cancel")
179 text: qsTr("Waiting for Vehicle to response to Cancel. This may take a few seconds.")
185 onWaitingForCancelChanged: {
186 if (!controller.waitingForCancel) {
195 id: singleCompassOnboardResultsComponent
198 anchors.left: parent.left
199 anchors.right: parent.right
200 spacing: Math.round(ScreenTools.defaultFontPixelHeight / 2)
201 visible: sensorParams.rgCompassAvailable[index] && sensorParams.rgCompassUseFact[index].value
203 property int _index: index
205 property real greenMaxThreshold: 8 * (sensorParams.rgCompassExternal[index] ? 1 : 2)
206 property real yellowMaxThreshold: 15 * (sensorParams.rgCompassExternal[index] ? 1 : 2)
207 property real fitnessRange: 25 * (sensorParams.rgCompassExternal[index] ? 1 : 2)
210 anchors.left: parent.left
211 anchors.right: parent.right
212 height: ScreenTools.defaultFontPixelHeight
219 width: parent.width * (greenMaxThreshold / fitnessRange)
220 height: parent.height
224 width: parent.width * ((yellowMaxThreshold - greenMaxThreshold) / fitnessRange)
225 height: parent.height
229 width: parent.width * ((fitnessRange - yellowMaxThreshold) / fitnessRange)
230 height: parent.height
236 height: fitnessRow.height * 0.66
238 anchors.verticalCenter: fitnessRow.verticalCenter
239 x: (fitnessRow.width * (Math.min(Math.max(controller.rgCompassCalFitness[index], 0.0), fitnessRange) / fitnessRange)) - (width / 2)
242 border.color: "black"
247 anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 2
248 anchors.left: parent.left
249 anchors.right: parent.right
250 sourceComponent: singleCompassSettingsComponent
252 property int index: _index
257 QGCPopupDialogFactory {
258 id: postOnboardCompassCalibrationFactory
260 dialogComponent: postOnboardCompassCalibrationComponent
264 id: postOnboardCompassCalibrationComponent
267 id: postOnboardCompassCalibrationDialog
268 title: qsTr("Calibration complete")
272 width: 40 * ScreenTools.defaultFontPixelWidth
273 spacing: ScreenTools.defaultFontPixelHeight
277 delegate: singleCompassOnboardResultsComponent
281 anchors.left: parent.left
282 anchors.right: parent.right
283 wrapMode: Text.WordWrap
284 text: qsTr("Shown in the indicator bars is the quality of the calibration for each compass.\n\n") +
285 qsTr("- Green indicates a well functioning compass.\n") +
286 qsTr("- Yellow indicates a questionable compass or calibration.\n") +
287 qsTr("- Red indicates a compass which should not be used.\n\n") +
288 qsTr("YOU MUST REBOOT YOUR VEHICLE AFTER EACH CALIBRATION.")
292 text: qsTr("Reboot Vehicle")
294 controller.vehicle.rebootVehicle()
295 postOnboardCompassCalibrationDialog.close()
303 id: postCalibrationComponent
306 id: postCalibrationDialog
307 title: qsTr("Calibration complete")
310 width: 40 * ScreenTools.defaultFontPixelWidth
311 spacing: ScreenTools.defaultFontPixelHeight
314 anchors.left: parent.left
315 anchors.right: parent.right
316 wrapMode: Text.WordWrap
317 text: qsTr("YOU MUST REBOOT YOUR VEHICLE AFTER EACH CALIBRATION.")
321 text: qsTr("Reboot Vehicle")
323 controller.vehicle.rebootVehicle()
324 postCalibrationDialog.close()
331 property bool _singleCompassSettingsComponentShowPriority: true
333 id: singleCompassSettingsComponent
336 spacing: Math.round(ScreenTools.defaultFontPixelHeight / 2)
337 visible: sensorParams.rgCompassAvailable[index]
340 text: compassLabel(index)
343 fact: sensorParams.rgCompassId[index]
347 anchors.margins: ScreenTools.defaultFontPixelWidth * 2
348 anchors.left: parent.left
349 spacing: Math.round(ScreenTools.defaultFontPixelHeight / 4)
352 spacing: ScreenTools.defaultFontPixelWidth
355 id: useCompassCheckBox
356 text: qsTr("Use Compass")
357 fact: sensorParams.rgCompassUseFact[index]
358 visible: sensorParams.rgCompassUseParamAvailable[index] && !sensorParams.rgCompassPrimary[index]
362 model: [ qsTr("Priority 1"), qsTr("Priority 2"), qsTr("Priority 3"), qsTr("Not Set") ]
363 visible: _singleCompassSettingsComponentShowPriority && sensorParams.compassPrioFactsAvailable && useCompassCheckBox.visible && useCompassCheckBox.checked
365 property int _compassIndex: index
367 function selectPriorityfromParams() {
369 var compassId = sensorParams.rgCompassId[_compassIndex].rawValue
370 for (var prioIndex=0; prioIndex<3; prioIndex++) {
371 console.log(`comparing ${compassId} with ${sensorParams.rgCompassPrio[prioIndex].rawValue} (index ${prioIndex})`)
372 if (compassId == sensorParams.rgCompassPrio[prioIndex].rawValue) {
373 currentIndex = prioIndex
379 Component.onCompleted: selectPriorityfromParams()
381 onActivated: (index) => {
383 // User cannot select Not Set
384 selectPriorityfromParams()
386 sensorParams.rgCompassPrio[index].rawValue = sensorParams.rgCompassId[_compassIndex].rawValue
393 visible: !_compassAutoRot && sensorParams.rgCompassExternal[index] && sensorParams.rgCompassRotParamAvailable[index]
395 QGCLabel { text: qsTr("Orientation:") }
398 width: rotationColumnWidth
400 fact: sensorParams.rgCompassRotFact[index]
407 QGCPopupDialogFactory {
408 id: orientationsDialogFactory
410 dialogComponent: orientationsDialogComponent
414 id: orientationsDialogComponent
417 function compassMask () {
419 mask |= (0 + (sensorParams.rgCompassPrio[0].rawValue !== 0)) << 0
420 mask |= (0 + (sensorParams.rgCompassPrio[1].rawValue !== 0)) << 1
421 mask |= (0 + (sensorParams.rgCompassPrio[2].rawValue !== 0)) << 2
426 if (_orientationDialogCalType == _calTypeAccel) {
427 controller.calibrateAccel(_doSimpleAccelCal)
428 } else if (_orientationDialogCalType == _calTypeCompass) {
429 if (!northCalibrationCheckBox.checked) {
430 controller.calibrateCompass()
432 var lat = parseFloat(northCalLat.text)
433 var lon = parseFloat(northCalLon.text)
434 if (useMapPositionCheckbox.checked) {
435 lat = _mapPosition.latitude
436 lon = _mapPosition.longitude
438 if (useGcsPositionCheckbox.checked) {
439 lat = _gcsPosition.latitude
440 lon = _gcsPosition.longitude
442 if (isNaN(lat) || isNaN(lon)) {
445 controller.calibrateCompassNorth(lat, lon, compassMask())
451 width: 40 * ScreenTools.defaultFontPixelWidth
452 spacing: ScreenTools.defaultFontPixelHeight
456 wrapMode: Text.WordWrap
457 text: _orientationDialogHelp
461 QGCLabel { text: qsTr("Autopilot Rotation:") }
464 width: rotationColumnWidth
472 visible: _orientationDialogCalType == _calTypeAccel
473 spacing: ScreenTools.defaultFontPixelHeight
477 wrapMode: Text.WordWrap
478 text: qsTr("Simple accelerometer calibration is less precise but allows calibrating without rotating the vehicle. Check this if you have a large/heavy vehicle.")
482 text: "Simple Accelerometer Calibration"
483 onClicked: _doSimpleAccelCal = this.checked
488 model: _orientationsDialogShowCompass ? 3 : 0
489 delegate: singleCompassSettingsComponent
493 id: magneticDeclinationLabel
495 visible: globals.activeVehicle.sub && _orientationsDialogShowCompass
496 text: qsTr("Magnetic Declination")
500 visible: magneticDeclinationLabel.visible
501 anchors.margins: ScreenTools.defaultFontPixelWidth
502 anchors.left: parent.left
503 anchors.right: parent.right
504 spacing: ScreenTools.defaultFontPixelHeight
507 id: manualMagneticDeclinationCheckBox
508 text: qsTr("Manual Magnetic Declination")
509 property Fact autoDecFact: controller.getParameterFact(-1, "COMPASS_AUTODEC")
510 property int manual: 0
511 property int automatic: 1
513 checked: autoDecFact.rawValue === manual
514 onClicked: autoDecFact.value = (checked ? manual : automatic)
518 fact: sensorParams.declinationFact
519 enabled: manualMagneticDeclinationCheckBox.checked
523 Item { height: ScreenTools.defaultFontPixelHeight; width: 10 } // spacer
526 id: northCalibrationLabel
528 visible: _orientationsDialogShowCompass
529 wrapMode: Text.WordWrap
530 text: qsTr("Fast compass calibration given vehicle position and yaw. This ") +
531 qsTr("results in zero diagonal and off-diagonal elements, so is only ") +
532 qsTr("suitable for vehicles where the field is close to spherical. It is ") +
533 qsTr("useful for large vehicles where moving the vehicle to calibrate it ") +
534 qsTr("is difficult. Point the vehicle North before using it.")
538 visible: northCalibrationLabel.visible
539 anchors.margins: ScreenTools.defaultFontPixelWidth
540 anchors.left: parent.left
541 anchors.right: parent.right
542 spacing: ScreenTools.defaultFontPixelHeight
545 id: northCalibrationCheckBox
546 visible: northCalibrationLabel.visible
547 text: qsTr("Fast Calibration")
551 id: northCalibrationManualPosition
553 visible: northCalibrationCheckBox.checked && !globals.activeVehicle.coordinate.isValid
554 wrapMode: Text.WordWrap
555 text: qsTr("Vehicle has no Valid positon, please provide it")
559 visible: northCalibrationManualPosition.visible && _gcsPosition.isValid
560 id: useGcsPositionCheckbox
561 text: qsTr("Use GCS position instead")
562 checked: _gcsPosition.isValid
565 visible: northCalibrationManualPosition.visible && !_gcsPosition.isValid
566 id: useMapPositionCheckbox
567 text: qsTr("Use current map position instead")
572 visible: useMapPositionCheckbox.checked
573 wrapMode: Text.WordWrap
574 text: qsTr(`Lat: ${_mapPosition.latitude.toFixed(4)} Lon: ${_mapPosition.longitude.toFixed(4)}`)
579 visible: !useGcsPositionCheckbox.checked && !useMapPositionCheckbox.checked && northCalibrationCheckBox.checked
581 textColor: isNaN(parseFloat(text)) ? qgcPal.warningText: qgcPal.textFieldText
582 enabled: !useGcsPositionCheckbox.checked
586 visible: !useGcsPositionCheckbox.checked && !useMapPositionCheckbox.checked && northCalibrationCheckBox.checked
588 textColor: isNaN(parseFloat(text)) ? qgcPal.warningText: qgcPal.textFieldText
589 enabled: !useGcsPositionCheckbox.checked
597 QGCPopupDialogFactory {
598 id: compassMotDialogFactory
600 dialogComponent: compassMotDialogComponent
604 id: compassMotDialogComponent
607 title: qsTr("Compass Motor Interference Calibration")
608 buttons: Dialog.Cancel | Dialog.Ok
610 onAccepted: controller.calibrateMotorInterference()
613 width: 40 * ScreenTools.defaultFontPixelWidth
614 spacing: ScreenTools.defaultFontPixelHeight
617 anchors.left: parent.left
618 anchors.right: parent.right
619 wrapMode: Text.WordWrap
620 text: qsTr("This is recommended for vehicles that have only an internal compass and on vehicles where there is significant interference on the compass from the motors, power wires, etc. ") +
621 qsTr("CompassMot only works well if you have a battery current monitor because the magnetic interference is linear with current drawn. ") +
622 qsTr("It is technically possible to set-up CompassMot using throttle but this is not recommended.")
626 anchors.left: parent.left
627 anchors.right: parent.right
628 wrapMode: Text.WordWrap
629 text: qsTr("Disconnect your props, flip them over and rotate them one position around the frame. ") +
630 qsTr("In this configuration they should push the copter down into the ground when the throttle is raised.")
634 anchors.left: parent.left
635 anchors.right: parent.right
636 wrapMode: Text.WordWrap
637 text: qsTr("Secure the copter (perhaps with tape) so that it does not move.")
641 anchors.left: parent.left
642 anchors.right: parent.right
643 wrapMode: Text.WordWrap
644 text: qsTr("Turn on your transmitter and keep throttle at zero.")
648 anchors.left: parent.left
649 anchors.right: parent.right
650 wrapMode: Text.WordWrap
651 text: qsTr("Click Ok to start CompassMot calibration.")
659 anchors.left: parent.left
660 anchors.top: parent.top
661 anchors.bottom: parent.bottom
663 contentHeight: nextCancelColumn.y + nextCancelColumn.height + _margins
665 // Calibration button column - Calibratin buttons are kept in a separate column from Next/Cancel buttons
666 // so we can enable/disable them all as a group
670 Layout.alignment: Qt.AlignLeft | Qt.AlignTop
674 text: qsTr("Accelerometer")
675 indicatorGreen: !accelCalNeeded
677 onClicked: function () {
678 showOrientationsDialog(_calTypeAccel);
679 showSimpleAccelCalOption();
685 text: qsTr("Compass")
686 indicatorGreen: !compassCalNeeded
689 if (controller.accelSetupNeeded) {
690 QGroundControl.showMessageDialog(sensorsPage, qsTr("Calibrate Compass"), qsTr("Accelerometer must be calibrated prior to Compass."))
692 showOrientationsDialog(_calTypeCompass)
699 text: _levelHorizonText
701 readonly property string _levelHorizonText: qsTr("Level Horizon")
704 if (controller.accelSetupNeeded) {
705 QGroundControl.showMessageDialog(sensorsPage, _levelHorizonText, qsTr("Accelerometer must be calibrated prior to Level Horizon."))
707 QGroundControl.showMessageDialog(sensorsPage, _levelHorizonText,
708 qsTr("To level the horizon you need to place the vehicle in its level flight position and press Ok."),
709 Dialog.Cancel | Dialog.Ok,
710 function() { controller.levelHorizon() })
718 visible: globals.activeVehicle && (globals.activeVehicle.multiRotor | globals.activeVehicle.rover | globals.activeVehicle.sub)
719 onClicked: QGroundControl.showMessageDialog(sensorsPage, qsTr("Calibrate Gyro"),
720 qsTr("For Gyroscope calibration you will need to place your vehicle on a surface and leave it still.\n\nClick Ok to start calibration."),
721 Dialog.Cancel | Dialog.Ok,
722 function() { controller.calibrateGyro() })
727 text: _calibratePressureText
728 onClicked: QGroundControl.showMessageDialog(sensorsPage, _calibratePressureText,
729 qsTr("Pressure calibration will set the %1 to zero at the current pressure reading. %2").arg(_altText).arg(_helpTextFW),
730 Dialog.Cancel | Dialog.Ok,
731 function() { controller.calibratePressure() })
733 readonly property string _altText: globals.activeVehicle.sub ? qsTr("depth") : qsTr("altitude")
734 readonly property string _helpTextFW: globals.activeVehicle.fixedWing ? qsTr("To calibrate the airspeed sensor shield it from the wind. Do not touch the sensor or obstruct any holes during the calibration.") : ""
735 readonly property string _calibratePressureText: globals.activeVehicle.fixedWing ? qsTr("Baro/Airspeed") : qsTr("Pressure")
740 text: qsTr("CompassMot")
741 visible: globals.activeVehicle ? globals.activeVehicle.supports.motorInterference : false
742 onClicked: compassMotDialogFactory.open()
747 text: qsTr("Sensor Settings")
748 onClicked: showOrientationsDialog(_calTypeSet)
750 } // Column - Cal Buttons
754 anchors.topMargin: buttonColumn.spacing
755 anchors.top: buttonColumn.bottom
756 anchors.left: buttonColumn.left
757 spacing: buttonColumn.spacing
764 onClicked: controller.nextClicked()
772 onClicked: controller.cancelCalibration()
775 } // QGCFlickable - buttons
777 /// Right column - cal area
779 anchors.leftMargin: _margins
780 anchors.top: parent.top
781 anchors.bottom: parent.bottom
782 anchors.left: buttonFlickable.right
783 anchors.right: parent.right
787 anchors.left: parent.left
788 anchors.right: parent.right
791 Item { height: ScreenTools.defaultFontPixelHeight; width: 10 } // spacer
796 height: parent.height - y
802 text: statusTextAreaDefaultText
804 background: Rectangle { color: qgcPal.windowShade }
808 id: orientationCalArea
810 visible: controller.showOrientationCalArea
811 color: qgcPal.windowShade
814 id: orientationCalAreaHelpText
815 anchors.margins: ScreenTools.defaultFontPixelWidth
816 anchors.top: orientationCalArea.top
817 anchors.left: orientationCalArea.left
819 wrapMode: Text.WordWrap
820 font.pointSize: ScreenTools.mediumFontPointSize
824 anchors.topMargin: ScreenTools.defaultFontPixelWidth
825 anchors.top: orientationCalAreaHelpText.bottom
826 anchors.bottom: parent.bottom
827 anchors.left: parent.left
828 anchors.right: parent.right
829 spacing: ScreenTools.defaultFontPixelWidth
831 property real indicatorWidth: (width / 3) - (spacing * 2)
832 property real indicatorHeight: (height / 2) - spacing
835 width: parent.indicatorWidth
836 height: parent.indicatorHeight
837 visible: controller.orientationCalDownSideVisible
838 calValid: controller.orientationCalDownSideDone
839 calInProgress: controller.orientationCalDownSideInProgress
840 calInProgressText: controller.orientationCalDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
841 imageSource: "qrc:///qmlimages/VehicleDown.png"
844 width: parent.indicatorWidth
845 height: parent.indicatorHeight
846 visible: controller.orientationCalLeftSideVisible
847 calValid: controller.orientationCalLeftSideDone
848 calInProgress: controller.orientationCalLeftSideInProgress
849 calInProgressText: controller.orientationCalLeftSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
850 imageSource: "qrc:///qmlimages/VehicleLeft.png"
853 width: parent.indicatorWidth
854 height: parent.indicatorHeight
855 visible: controller.orientationCalRightSideVisible
856 calValid: controller.orientationCalRightSideDone
857 calInProgress: controller.orientationCalRightSideInProgress
858 calInProgressText: controller.orientationCalRightSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
859 imageSource: "qrc:///qmlimages/VehicleRight.png"
862 width: parent.indicatorWidth
863 height: parent.indicatorHeight
864 visible: controller.orientationCalNoseDownSideVisible
865 calValid: controller.orientationCalNoseDownSideDone
866 calInProgress: controller.orientationCalNoseDownSideInProgress
867 calInProgressText: controller.orientationCalNoseDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
868 imageSource: "qrc:///qmlimages/VehicleNoseDown.png"
871 width: parent.indicatorWidth
872 height: parent.indicatorHeight
873 visible: controller.orientationCalTailDownSideVisible
874 calValid: controller.orientationCalTailDownSideDone
875 calInProgress: controller.orientationCalTailDownSideInProgress
876 calInProgressText: controller.orientationCalTailDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
877 imageSource: "qrc:///qmlimages/VehicleTailDown.png"
880 width: parent.indicatorWidth
881 height: parent.indicatorHeight
882 visible: controller.orientationCalUpsideDownSideVisible
883 calValid: controller.orientationCalUpsideDownSideDone
884 calInProgress: controller.orientationCalUpsideDownSideInProgress
885 calInProgressText: controller.orientationCalUpsideDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still")
886 imageSource: "qrc:///qmlimages/VehicleUpsideDown.png"
890 } // Item - Cal display area
891 } // Column - cal display
893 } // Component - sensorsPageComponent