diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml
index 4148cd0..82a1ad6 100644
--- a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml
+++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml
@@ -569,6 +569,26 @@ SetupPage {
                 } // QGCViewDialog
             } // Component - calibratePressureDialogComponent
 
+            Component {
+                id: calibrateGyroDialogComponent
+
+                QGCViewDialog {
+                    id: calibrateGyroDialog
+
+                    function accept() {
+                        controller.calibrateGyro()
+                        calibrateGyroDialog.hideDialog()
+                    }
+
+                    QGCLabel {
+                        anchors.left:   parent.left
+                        anchors.right:  parent.right
+                        wrapMode:       Text.WordWrap
+                        text:           qsTr("For Gyroscope calibration you will need to place your vehicle on a surface and leave it still.\n\nClick Ok to start calibration.")
+                    }
+                }
+            }
+
             QGCFlickable {
                 id:             buttonFlickable
                 anchors.left:   parent.left
@@ -623,10 +643,17 @@ SetupPage {
 
                     QGCButton {
                         width:      _buttonWidth
+                        text:       qsTr("Gyro")
+                        visible:    activeVehicle && (activeVehicle.multiRotor | activeVehicle.rover)
+                        onClicked:  mainWindow.showComponentDialog(calibrateGyroDialogComponent, qsTr("Calibrate Gyro"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
+                    }
+
+                    QGCButton {
+                        width:      _buttonWidth
                         text:       _calibratePressureText
                         onClicked:  mainWindow.showComponentDialog(calibratePressureDialogComponent, _calibratePressureText, mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
 
-                        readonly property string _calibratePressureText: activeVehicle.fixedWing ? qsTr("Cal Baro/Airspeed") : qsTr("Calibrate Pressure")
+                        readonly property string _calibratePressureText: activeVehicle.fixedWing ? qsTr("Baro/Airspeed") : qsTr("Pressure")
                     }
 
                     QGCButton {
diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
index 758d300..f2dbe92 100644
--- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
+++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
@@ -294,7 +294,7 @@ void APMSensorsComponentController::calibrateAccel(void)
     _calTypeInProgress = CalTypeAccel;
     _vehicle->setConnectionLostEnabled(false);
     _startLogCalibration();
-    _uas->startCalibration(UASInterface::StartCalibrationAccel);
+    _vehicle->startCalibration(Vehicle::CalibrationAccel);
 }
 
 void APMSensorsComponentController::calibrateMotorInterference(void)
@@ -305,7 +305,7 @@ void APMSensorsComponentController::calibrateMotorInterference(void)
     _appendStatusLog(tr("Raise the throttle slowly to between 50% ~ 75% (the props will spin!) for 5 ~ 10 seconds."));
     _appendStatusLog(tr("Quickly bring the throttle back down to zero"));
     _appendStatusLog(tr("Press the Next button to complete the calibration"));
-    _uas->startCalibration(UASInterface::StartCalibrationCompassMot);
+    _vehicle->startCalibration(Vehicle::CalibrationAPMCompassMot);
 }
 
 void APMSensorsComponentController::levelHorizon(void)
@@ -314,7 +314,7 @@ void APMSensorsComponentController::levelHorizon(void)
     _vehicle->setConnectionLostEnabled(false);
     _startLogCalibration();
     _appendStatusLog(tr("Hold the vehicle in its level flight position."));
-    _uas->startCalibration(UASInterface::StartCalibrationLevel);
+    _vehicle->startCalibration(Vehicle::CalibrationLevel);
 }
 
 void APMSensorsComponentController::calibratePressure(void)
@@ -323,7 +323,16 @@ void APMSensorsComponentController::calibratePressure(void)
     _vehicle->setConnectionLostEnabled(false);
     _startLogCalibration();
     _appendStatusLog(tr("Requesting pressure calibration..."));
-    _uas->startCalibration(UASInterface::StartCalibrationPressure);
+    _vehicle->startCalibration(Vehicle::CalibrationAPMPressureAirspeed);
+}
+
+void APMSensorsComponentController::calibrateGyro(void)
+{
+    _calTypeInProgress = CalTypeGyro;
+    _vehicle->setConnectionLostEnabled(false);
+    _startLogCalibration();
+    _appendStatusLog(tr("Requesting gyro calibration..."));
+    _vehicle->startCalibration(Vehicle::CalibrationGyro);
 }
 
 void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
@@ -444,203 +453,6 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
         _stopCalibration(StopCalibrationFailed);
         return;
     }
-
-#if 0
-
-    if (text.contains(QLatin1Literal("progress <"))) {
-        QString percent = text.split("<").last().split(">").first();
-        bool ok;
-        int p = percent.toInt(&ok);
-        if (ok && _progressBar) {
-            _progressBar->setProperty("value", (float)(p / 100.0));
-        }
-        return;
-    }
-
-    QString anyKey(QStringLiteral("and press any"));
-    if (text.contains(anyKey)) {
-        text = text.left(text.indexOf(anyKey)) + QStringLiteral("and click Next to continue.");
-        _nextButton->setEnabled(true);
-    }
-
-    _appendStatusLog(text);
-    qCDebug(APMSensorsComponentControllerLog) << text << severity;
-
-    if (text.contains(QLatin1String("Calibration successful"))) {
-        _stopCalibration(StopCalibrationSuccess);
-        return;
-    }
-
-    if (text.contains(QLatin1String("FAILED"))) {
-        _stopCalibration(StopCalibrationFailed);
-        return;
-    }
-
-    // All calibration messages start with [cal]
-    QString calPrefix(QStringLiteral("[cal] "));
-    if (!text.startsWith(calPrefix)) {
-        return;
-    }
-    text = text.right(text.length() - calPrefix.length());
-
-    QString calStartPrefix(QStringLiteral("calibration started: "));
-    if (text.startsWith(calStartPrefix)) {
-        text = text.right(text.length() - calStartPrefix.length());
-        
-        _startVisualCalibration();
-        
-        if (text == QLatin1Literal("accel") || text == QLatin1Literal("mag") || text == QLatin1Literal("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") {
-                _calTypeInProgress = CalTypeAccel;
-                _orientationCalDownSideVisible = true;
-                _orientationCalUpsideDownSideVisible = true;
-                _orientationCalLeftSideVisible = true;
-                _orientationCalRightSideVisible = true;
-                _orientationCalTailDownSideVisible = true;
-                _orientationCalNoseDownSideVisible = true;
-            } else if (text == "mag") {
-                _calTypeInProgress = CalTypeOffboardCompass;
-                _orientationCalDownSideVisible = true;
-                _orientationCalUpsideDownSideVisible = true;
-                _orientationCalLeftSideVisible = true;
-                _orientationCalRightSideVisible = true;
-                _orientationCalTailDownSideVisible = true;
-                _orientationCalNoseDownSideVisible = true;
-            } else {
-                Q_ASSERT(false);
-            }
-            emit orientationCalSidesDoneChanged();
-            emit orientationCalSidesVisibleChanged();
-            emit orientationCalSidesInProgressChanged();
-            _updateAndEmitShowOrientationCalArea(true);
-        }
-        return;
-    }
-    
-    if (text.endsWith(QLatin1Literal("orientation detected"))) {
-        QString side = text.section(" ", 0, 0);
-        qDebug() << "Side started" << side;
-        
-        if (side == QLatin1Literal("down")) {
-            _orientationCalDownSideInProgress = true;
-            if (_calTypeInProgress == CalTypeOffboardCompass) {
-                _orientationCalDownSideRotate = true;
-            }
-        } else if (side == QLatin1Literal("up")) {
-            _orientationCalUpsideDownSideInProgress = true;
-            if (_calTypeInProgress == CalTypeOffboardCompass) {
-                _orientationCalUpsideDownSideRotate = true;
-            }
-        } else if (side == QLatin1Literal("left")) {
-            _orientationCalLeftSideInProgress = true;
-            if (_calTypeInProgress == CalTypeOffboardCompass) {
-                _orientationCalLeftSideRotate = true;
-            }
-        } else if (side == QLatin1Literal("right")) {
-            _orientationCalRightSideInProgress = true;
-            if (_calTypeInProgress == CalTypeOffboardCompass) {
-                _orientationCalRightSideRotate = true;
-            }
-        } else if (side == QLatin1Literal("front")) {
-            _orientationCalNoseDownSideInProgress = true;
-            if (_calTypeInProgress == CalTypeOffboardCompass) {
-                _orientationCalNoseDownSideRotate = true;
-            }
-        } else if (side == QLatin1Literal("back")) {
-            _orientationCalTailDownSideInProgress = true;
-            if (_calTypeInProgress == CalTypeOffboardCompass) {
-                _orientationCalTailDownSideRotate = true;
-            }
-        }
-        
-        if (_calTypeInProgress == CalTypeOffboardCompass) {
-            _orientationCalAreaHelpText->setProperty("text", tr("Rotate the vehicle continuously as shown in the diagram until marked as Completed"));
-        } else {
-            _orientationCalAreaHelpText->setProperty("text", tr("Hold still in the current orientation"));
-        }
-        
-        emit orientationCalSidesInProgressChanged();
-        emit orientationCalSidesRotateChanged();
-        return;
-    }
-    
-    if (text.endsWith(QLatin1Literal("side done, rotate to a different side"))) {
-        QString side = text.section(" ", 0, 0);
-        qDebug() << "Side finished" << side;
-        
-        if (side == QLatin1Literal("down")) {
-            _orientationCalDownSideInProgress = false;
-            _orientationCalDownSideDone = true;
-            _orientationCalDownSideRotate = false;
-        } else if (side == QLatin1Literal("up")) {
-            _orientationCalUpsideDownSideInProgress = false;
-            _orientationCalUpsideDownSideDone = true;
-            _orientationCalUpsideDownSideRotate = false;
-        } else if (side == QLatin1Literal("left")) {
-            _orientationCalLeftSideInProgress = false;
-            _orientationCalLeftSideDone = true;
-            _orientationCalLeftSideRotate = false;
-        } else if (side == QLatin1Literal("right")) {
-            _orientationCalRightSideInProgress = false;
-            _orientationCalRightSideDone = true;
-            _orientationCalRightSideRotate = false;
-        } else if (side == QLatin1Literal("front")) {
-            _orientationCalNoseDownSideInProgress = false;
-            _orientationCalNoseDownSideDone = true;
-            _orientationCalNoseDownSideRotate = false;
-        } else if (side == QLatin1Literal("back")) {
-            _orientationCalTailDownSideInProgress = false;
-            _orientationCalTailDownSideDone = true;
-            _orientationCalTailDownSideRotate = false;
-        }
-        
-        _orientationCalAreaHelpText->setProperty("text", tr("Place you vehicle into one of the orientations shown below and hold it still"));
-
-        emit orientationCalSidesInProgressChanged();
-        emit orientationCalSidesDoneChanged();
-        emit orientationCalSidesRotateChanged();
-        return;
-    }
-    
-    if (text.startsWith(QLatin1Literal("calibration done:"))) {
-        _stopCalibration(StopCalibrationSuccess);
-        return;
-    }
-
-    if (text.startsWith(QLatin1Literal("calibration cancelled"))) {
-        _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
-        return;
-    }
-
-    if (text.startsWith(QLatin1Literal("calibration failed"))) {
-        _stopCalibration(StopCalibrationFailed);
-        return;
-    }
-#endif
 }
 
 void APMSensorsComponentController::_refreshParams(void)
@@ -685,7 +497,7 @@ void APMSensorsComponentController::cancelCalibration(void)
         emit waitingForCancelChanged();
         // The firmware doesn't always allow us to cancel calibration. The best we can do is wait
         // for it to timeout.
-        _uas->stopCalibration();
+        _vehicle->stopCalibration();
     }
 
 }
@@ -728,36 +540,18 @@ bool APMSensorsComponentController::usingUDPLink(void)
 
 void APMSensorsComponentController::_handleCommandAck(mavlink_message_t& message)
 {
-    if (_calTypeInProgress == CalTypeLevelHorizon) {
-        mavlink_command_ack_t commandAck;
-        mavlink_msg_command_ack_decode(&message, &commandAck);
-
-        if (commandAck.command == MAV_CMD_PREFLIGHT_CALIBRATION) {
-            switch (commandAck.result) {
-            case MAV_RESULT_ACCEPTED:
-                _appendStatusLog(tr("Level horizon complete"));
-                _stopCalibration(StopCalibrationSuccessShowLog);
-                break;
-            default:
-                _appendStatusLog(tr("Level horizon failed"));
-                _stopCalibration(StopCalibrationFailed);
-                break;
-            }
-        }
-    }
-
-    if (_calTypeInProgress == CalTypePressure) {
+    if (_calTypeInProgress == CalTypeLevelHorizon || _calTypeInProgress == CalTypeGyro || _calTypeInProgress == CalTypePressure) {
         mavlink_command_ack_t commandAck;
         mavlink_msg_command_ack_decode(&message, &commandAck);
 
         if (commandAck.command == MAV_CMD_PREFLIGHT_CALIBRATION) {
             switch (commandAck.result) {
             case MAV_RESULT_ACCEPTED:
-                _appendStatusLog(tr("Pressure calibration success"));
+                _appendStatusLog(tr("Successfully completed"));
                 _stopCalibration(StopCalibrationSuccessShowLog);
                 break;
             default:
-                _appendStatusLog(tr("Pressure calibration fail"));
+                _appendStatusLog(tr("Failed"));
                 _stopCalibration(StopCalibrationFailed);
                 break;
             }
diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.h b/src/AutoPilotPlugins/APM/APMSensorsComponentController.h
index 238d403..b06f733 100644
--- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.h
+++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.h
@@ -7,9 +7,7 @@
  *
  ****************************************************************************/
 
-
-#ifndef APMSensorsComponentController_H
-#define APMSensorsComponentController_H
+#pragma once
 
 #include <QObject>
 
@@ -31,70 +29,72 @@ public:
     APMSensorsComponentController(void);
     ~APMSensorsComponentController();
 
-    Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
-    Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
+    Q_PROPERTY(QQuickItem* statusLog                        MEMBER _statusLog)
+    Q_PROPERTY(QQuickItem* progressBar                      MEMBER _progressBar)
     
-    Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton)
-    Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
-    Q_PROPERTY(QQuickItem* orientationCalAreaHelpText MEMBER _orientationCalAreaHelpText)
+    Q_PROPERTY(QQuickItem* nextButton                       MEMBER _nextButton)
+    Q_PROPERTY(QQuickItem* cancelButton                     MEMBER _cancelButton)
+    Q_PROPERTY(QQuickItem* orientationCalAreaHelpText       MEMBER _orientationCalAreaHelpText)
 
-    Q_PROPERTY(bool compassSetupNeeded  READ compassSetupNeeded NOTIFY setupNeededChanged)
-    Q_PROPERTY(bool accelSetupNeeded    READ accelSetupNeeded   NOTIFY setupNeededChanged)
+    Q_PROPERTY(bool compassSetupNeeded                      READ compassSetupNeeded                         NOTIFY setupNeededChanged)
+    Q_PROPERTY(bool accelSetupNeeded                        READ accelSetupNeeded                           NOTIFY setupNeededChanged)
 
-    Q_PROPERTY(bool showOrientationCalArea MEMBER _showOrientationCalArea NOTIFY showOrientationCalAreaChanged)
+    Q_PROPERTY(bool showOrientationCalArea                  MEMBER _showOrientationCalArea                  NOTIFY showOrientationCalAreaChanged)
     
-    Q_PROPERTY(bool orientationCalDownSideDone MEMBER _orientationCalDownSideDone NOTIFY orientationCalSidesDoneChanged)
-    Q_PROPERTY(bool orientationCalUpsideDownSideDone MEMBER _orientationCalUpsideDownSideDone NOTIFY orientationCalSidesDoneChanged)
-    Q_PROPERTY(bool orientationCalLeftSideDone MEMBER _orientationCalLeftSideDone NOTIFY orientationCalSidesDoneChanged)
-    Q_PROPERTY(bool orientationCalRightSideDone MEMBER _orientationCalRightSideDone NOTIFY orientationCalSidesDoneChanged)
-    Q_PROPERTY(bool orientationCalNoseDownSideDone MEMBER _orientationCalNoseDownSideDone NOTIFY orientationCalSidesDoneChanged)
-    Q_PROPERTY(bool orientationCalTailDownSideDone MEMBER _orientationCalTailDownSideDone NOTIFY orientationCalSidesDoneChanged)
+    Q_PROPERTY(bool orientationCalDownSideDone              MEMBER _orientationCalDownSideDone              NOTIFY orientationCalSidesDoneChanged)
+    Q_PROPERTY(bool orientationCalUpsideDownSideDone        MEMBER _orientationCalUpsideDownSideDone        NOTIFY orientationCalSidesDoneChanged)
+    Q_PROPERTY(bool orientationCalLeftSideDone              MEMBER _orientationCalLeftSideDone              NOTIFY orientationCalSidesDoneChanged)
+    Q_PROPERTY(bool orientationCalRightSideDone             MEMBER _orientationCalRightSideDone             NOTIFY orientationCalSidesDoneChanged)
+    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 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)
-    Q_PROPERTY(bool orientationCalRightSideInProgress MEMBER _orientationCalRightSideInProgress NOTIFY orientationCalSidesInProgressChanged)
-    Q_PROPERTY(bool orientationCalNoseDownSideInProgress MEMBER _orientationCalNoseDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
-    Q_PROPERTY(bool orientationCalTailDownSideInProgress MEMBER _orientationCalTailDownSideInProgress NOTIFY orientationCalSidesInProgressChanged)
+    Q_PROPERTY(bool orientationCalDownSideInProgress        MEMBER _orientationCalDownSideInProgress        NOTIFY orientationCalSidesInProgressChanged)
+    Q_PROPERTY(bool orientationCalUpsideDownSideInProgress  MEMBER _orientationCalUpsideDownSideInProgress  NOTIFY orientationCalSidesInProgressChanged)
+    Q_PROPERTY(bool orientationCalLeftSideInProgress        MEMBER _orientationCalLeftSideInProgress        NOTIFY orientationCalSidesInProgressChanged)
+    Q_PROPERTY(bool orientationCalRightSideInProgress       MEMBER _orientationCalRightSideInProgress       NOTIFY orientationCalSidesInProgressChanged)
+    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 orientationCalUpsideDownSideRotate MEMBER _orientationCalUpsideDownSideRotate NOTIFY orientationCalSidesRotateChanged)
-    Q_PROPERTY(bool orientationCalLeftSideRotate MEMBER _orientationCalLeftSideRotate NOTIFY orientationCalSidesRotateChanged)
-    Q_PROPERTY(bool orientationCalRightSideRotate MEMBER _orientationCalRightSideRotate NOTIFY orientationCalSidesRotateChanged)
-    Q_PROPERTY(bool orientationCalNoseDownSideRotate MEMBER _orientationCalNoseDownSideRotate NOTIFY orientationCalSidesRotateChanged)
-    Q_PROPERTY(bool orientationCalTailDownSideRotate MEMBER _orientationCalTailDownSideRotate NOTIFY orientationCalSidesRotateChanged)
+    Q_PROPERTY(bool orientationCalDownSideRotate            MEMBER _orientationCalDownSideRotate            NOTIFY orientationCalSidesRotateChanged)
+    Q_PROPERTY(bool orientationCalUpsideDownSideRotate      MEMBER _orientationCalUpsideDownSideRotate      NOTIFY orientationCalSidesRotateChanged)
+    Q_PROPERTY(bool orientationCalLeftSideRotate            MEMBER _orientationCalLeftSideRotate            NOTIFY orientationCalSidesRotateChanged)
+    Q_PROPERTY(bool orientationCalRightSideRotate           MEMBER _orientationCalRightSideRotate           NOTIFY orientationCalSidesRotateChanged)
+    Q_PROPERTY(bool orientationCalNoseDownSideRotate        MEMBER _orientationCalNoseDownSideRotate        NOTIFY orientationCalSidesRotateChanged)
+    Q_PROPERTY(bool orientationCalTailDownSideRotate        MEMBER _orientationCalTailDownSideRotate        NOTIFY orientationCalSidesRotateChanged)
     
-    Q_PROPERTY(bool waitingForCancel MEMBER _waitingForCancel NOTIFY waitingForCancelChanged)
+    Q_PROPERTY(bool waitingForCancel                        MEMBER _waitingForCancel                        NOTIFY waitingForCancelChanged)
 
-    Q_PROPERTY(bool compass1CalSucceeded READ compass1CalSucceeded NOTIFY compass1CalSucceededChanged)
-    Q_PROPERTY(bool compass2CalSucceeded READ compass2CalSucceeded NOTIFY compass2CalSucceededChanged)
-    Q_PROPERTY(bool compass3CalSucceeded READ compass3CalSucceeded NOTIFY compass3CalSucceededChanged)
+    Q_PROPERTY(bool compass1CalSucceeded                    READ compass1CalSucceeded                       NOTIFY compass1CalSucceededChanged)
+    Q_PROPERTY(bool compass2CalSucceeded                    READ compass2CalSucceeded                       NOTIFY compass2CalSucceededChanged)
+    Q_PROPERTY(bool compass3CalSucceeded                    READ compass3CalSucceeded                       NOTIFY compass3CalSucceededChanged)
 
-    Q_PROPERTY(double compass1CalFitness READ compass1CalFitness NOTIFY compass1CalFitnessChanged)
-    Q_PROPERTY(double compass2CalFitness READ compass2CalFitness NOTIFY compass2CalFitnessChanged)
-    Q_PROPERTY(double compass3CalFitness READ compass3CalFitness NOTIFY compass3CalFitnessChanged)
+    Q_PROPERTY(double compass1CalFitness                    READ compass1CalFitness                         NOTIFY compass1CalFitnessChanged)
+    Q_PROPERTY(double compass2CalFitness                    READ compass2CalFitness                         NOTIFY compass2CalFitnessChanged)
+    Q_PROPERTY(double compass3CalFitness                    READ compass3CalFitness                         NOTIFY compass3CalFitnessChanged)
 
-    Q_INVOKABLE void calibrateCompass(void);
-    Q_INVOKABLE void calibrateAccel(void);
-    Q_INVOKABLE void calibrateMotorInterference(void);
-    Q_INVOKABLE void levelHorizon(void);
-    Q_INVOKABLE void calibratePressure(void);
-    Q_INVOKABLE void cancelCalibration(void);
-    Q_INVOKABLE void nextClicked(void);
-    Q_INVOKABLE bool usingUDPLink(void);
+    Q_INVOKABLE void calibrateCompass           (void);
+    Q_INVOKABLE void calibrateAccel             (void);
+    Q_INVOKABLE void calibrateGyro              (void);
+    Q_INVOKABLE void calibrateMotorInterference (void);
+    Q_INVOKABLE void levelHorizon               (void);
+    Q_INVOKABLE void calibratePressure          (void);
+    Q_INVOKABLE void cancelCalibration          (void);
+    Q_INVOKABLE void nextClicked                (void);
+    Q_INVOKABLE bool usingUDPLink               (void);
 
-    bool compassSetupNeeded(void) const;
-    bool accelSetupNeeded(void) const;
+    bool compassSetupNeeded (void) const;
+    bool accelSetupNeeded   (void) const;
 
     typedef enum {
         CalTypeAccel,
+        CalTypeGyro,
         CalTypeOnboardCompass,
         CalTypeOffboardCompass,
         CalTypeLevelHorizon,
@@ -113,40 +113,40 @@ public:
     double compass3CalFitness(void) const { return _rgCompassCalFitness[2]; }
 
 signals:
-    void showGyroCalAreaChanged(void);
-    void showOrientationCalAreaChanged(void);
-    void orientationCalSidesDoneChanged(void);
-    void orientationCalSidesVisibleChanged(void);
-    void orientationCalSidesInProgressChanged(void);
-    void orientationCalSidesRotateChanged(void);
-    void resetStatusTextArea(void);
-    void waitingForCancelChanged(void);
-    void setupNeededChanged(void);
-    void calibrationComplete(CalType_t calType);
-    void compass1CalSucceededChanged(bool compass1CalSucceeded);
-    void compass2CalSucceededChanged(bool compass2CalSucceeded);
-    void compass3CalSucceededChanged(bool compass3CalSucceeded);
-    void compass1CalFitnessChanged(double compass1CalFitness);
-    void compass2CalFitnessChanged(double compass2CalFitness);
-    void compass3CalFitnessChanged(double compass3CalFitness);
-    void setAllCalButtonsEnabled(bool enabled);
+    void showGyroCalAreaChanged                 (void);
+    void showOrientationCalAreaChanged          (void);
+    void orientationCalSidesDoneChanged         (void);
+    void orientationCalSidesVisibleChanged      (void);
+    void orientationCalSidesInProgressChanged   (void);
+    void orientationCalSidesRotateChanged       (void);
+    void resetStatusTextArea                    (void);
+    void waitingForCancelChanged                (void);
+    void setupNeededChanged                     (void);
+    void calibrationComplete                    (CalType_t calType);
+    void compass1CalSucceededChanged            (bool compass1CalSucceeded);
+    void compass2CalSucceededChanged            (bool compass2CalSucceeded);
+    void compass3CalSucceededChanged            (bool compass3CalSucceeded);
+    void compass1CalFitnessChanged              (double compass1CalFitness);
+    void compass2CalFitnessChanged              (double compass2CalFitness);
+    void compass3CalFitnessChanged              (double compass3CalFitness);
+    void setAllCalButtonsEnabled                (bool enabled);
 
 private slots:
-    void _handleUASTextMessage(int uasId, int compId, int severity, QString text);
+    void _handleUASTextMessage  (int uasId, int compId, int severity, QString text);
     void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
-    void _mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
+    void _mavCommandResult      (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
 
 private:
-    void _startLogCalibration(void);
-    void _startVisualCalibration(void);
-    void _appendStatusLog(const QString& text);
-    void _refreshParams(void);
-    void _hideAllCalAreas(void);
-    void _resetInternalState(void);
-    void _handleCommandAck(mavlink_message_t& message);
-    void _handleMagCalProgress(mavlink_message_t& message);
-    void _handleMagCalReport(mavlink_message_t& message);
-    void _restorePreviousCompassCalFitness(void);
+    void _startLogCalibration               (void);
+    void _startVisualCalibration            (void);
+    void _appendStatusLog                   (const QString& text);
+    void _refreshParams                     (void);
+    void _hideAllCalAreas                   (void);
+    void _resetInternalState                (void);
+    void _handleCommandAck                  (mavlink_message_t& message);
+    void _handleMagCalProgress              (mavlink_message_t& message);
+    void _handleMagCalReport                (mavlink_message_t& message);
+    void _restorePreviousCompassCalFitness  (void);
 
     enum StopCalibrationCode {
         StopCalibrationSuccess,
@@ -212,5 +212,3 @@ private:
     
     static const int _supportedFirmwareCalVersion = 2;
 };
-
-#endif