diff --git a/qgcresources.qrc b/qgcresources.qrc
index 866038e..3b76854 100644
--- a/qgcresources.qrc
+++ b/qgcresources.qrc
@@ -56,7 +56,6 @@
         <file alias="px4.png">resources/firmware/px4.png</file>
     </qresource>
     <qresource prefix="/res/calibration">
-        <file alias="joystick.svg">resources/calibration/joystick/joystick.svg</file>
         <file alias="accel_back.png">resources/calibration/accel_back.png</file>
         <file alias="accel_down.png">resources/calibration/accel_down.png</file>
         <file alias="accel_front.png">resources/calibration/accel_front.png</file>
@@ -99,48 +98,4 @@
     <qresource prefix="/opengl">
         <file>resources/opengl/buglist.json</file>
     </qresource>
-    <qresource prefix="/qml/calibration/joystick/mode1">
-        <file alias="joystickCenter.png">resources/calibration/joystick/mode1/joystickCenter.png</file>
-        <file alias="joystickPitchDown.png">resources/calibration/joystick/mode1/joystickPitchDown.png</file>
-        <file alias="joystickPitchUp.png">resources/calibration/joystick/mode1/joystickPitchUp.png</file>
-        <file alias="joystickRollLeft.png">resources/calibration/joystick/mode1/joystickRollLeft.png</file>
-        <file alias="joystickRollRight.png">resources/calibration/joystick/mode1/joystickRollRight.png</file>
-        <file alias="joystickThrottleDown.png">resources/calibration/joystick/mode1/joystickThrottleDown.png</file>
-        <file alias="joystickThrottleUp.png">resources/calibration/joystick/mode1/joystickThrottleUp.png</file>
-        <file alias="joystickYawLeft.png">resources/calibration/joystick/mode1/joystickYawLeft.png</file>
-        <file alias="joystickYawRight.png">resources/calibration/joystick/mode1/joystickYawRight.png</file>
-    </qresource>
-    <qresource prefix="/qml/calibration/joystick/mode2">
-        <file alias="joystickCenter.png">resources/calibration/joystick/mode2/joystickCenter.png</file>
-        <file alias="joystickPitchDown.png">resources/calibration/joystick/mode2/joystickPitchDown.png</file>
-        <file alias="joystickPitchUp.png">resources/calibration/joystick/mode2/joystickPitchUp.png</file>
-        <file alias="joystickRollLeft.png">resources/calibration/joystick/mode2/joystickRollLeft.png</file>
-        <file alias="joystickRollRight.png">resources/calibration/joystick/mode2/joystickRollRight.png</file>
-        <file alias="joystickThrottleDown.png">resources/calibration/joystick/mode2/joystickThrottleDown.png</file>
-        <file alias="joystickThrottleUp.png">resources/calibration/joystick/mode2/joystickThrottleUp.png</file>
-        <file alias="joystickYawLeft.png">resources/calibration/joystick/mode2/joystickYawLeft.png</file>
-        <file alias="joystickYawRight.png">resources/calibration/joystick/mode2/joystickYawRight.png</file>
-    </qresource>
-    <qresource prefix="/qml/calibration/joystick/mode3">
-        <file alias="joystickCenter.png">resources/calibration/joystick/mode3/joystickCenter.png</file>
-        <file alias="joystickPitchDown.png">resources/calibration/joystick/mode3/joystickPitchDown.png</file>
-        <file alias="joystickPitchUp.png">resources/calibration/joystick/mode3/joystickPitchUp.png</file>
-        <file alias="joystickRollLeft.png">resources/calibration/joystick/mode3/joystickRollLeft.png</file>
-        <file alias="joystickRollRight.png">resources/calibration/joystick/mode3/joystickRollRight.png</file>
-        <file alias="joystickThrottleDown.png">resources/calibration/joystick/mode3/joystickThrottleDown.png</file>
-        <file alias="joystickThrottleUp.png">resources/calibration/joystick/mode3/joystickThrottleUp.png</file>
-        <file alias="joystickYawLeft.png">resources/calibration/joystick/mode3/joystickYawLeft.png</file>
-        <file alias="joystickYawRight.png">resources/calibration/joystick/mode3/joystickYawRight.png</file>
-    </qresource>
-    <qresource prefix="/qml/calibration/joystick/mode4">
-        <file alias="joystickCenter.png">resources/calibration/joystick/mode4/joystickCenter.png</file>
-        <file alias="joystickPitchDown.png">resources/calibration/joystick/mode4/joystickPitchDown.png</file>
-        <file alias="joystickPitchUp.png">resources/calibration/joystick/mode4/joystickPitchUp.png</file>
-        <file alias="joystickRollLeft.png">resources/calibration/joystick/mode4/joystickRollLeft.png</file>
-        <file alias="joystickRollRight.png">resources/calibration/joystick/mode4/joystickRollRight.png</file>
-        <file alias="joystickThrottleDown.png">resources/calibration/joystick/mode4/joystickThrottleDown.png</file>
-        <file alias="joystickThrottleUp.png">resources/calibration/joystick/mode4/joystickThrottleUp.png</file>
-        <file alias="joystickYawLeft.png">resources/calibration/joystick/mode4/joystickYawLeft.png</file>
-        <file alias="joystickYawRight.png">resources/calibration/joystick/mode4/joystickYawRight.png</file>
-    </qresource>
 </RCC>
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index f765d57..076561b 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -38,6 +38,10 @@
         <file alias="HealthPageWidget.qml">src/FlightMap/Widgets/HealthPageWidget.qml</file>
         <file alias="HelpSettings.qml">src/ui/preferences/HelpSettings.qml</file>
         <file alias="JoystickConfig.qml">src/VehicleSetup/JoystickConfig.qml</file>
+        <file alias="JoystickConfigButtons.qml">src/VehicleSetup/JoystickConfigButtons.qml</file>
+        <file alias="JoystickConfigAdvanced.qml">src/VehicleSetup/JoystickConfigAdvanced.qml</file>
+        <file alias="JoystickConfigGeneral.qml">src/VehicleSetup/JoystickConfigGeneral.qml</file>
+        <file alias="JoystickConfigCalibration.qml">src/VehicleSetup/JoystickConfigCalibration.qml</file>
         <file alias="LinkSettings.qml">src/ui/preferences/LinkSettings.qml</file>
         <file alias="LogDownloadPage.qml">src/AnalyzeView/LogDownloadPage.qml</file>
         <file alias="LogReplaySettings.qml">src/ui/preferences/LogReplaySettings.qml</file>
@@ -60,6 +64,7 @@
         <file alias="QGCViewDialogContainer.qml">src/QmlControls/QGCViewDialogContainer.qml</file>
         <file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
         <file alias="QGroundControl/Controls/AppMessages.qml">src/QmlControls/AppMessages.qml</file>
+        <file alias="QGroundControl/Controls/AxisMonitor.qml">src/QmlControls/AxisMonitor.qml</file>
         <file alias="QGroundControl/Controls/CameraCalc.qml">src/PlanView/CameraCalc.qml</file>
         <file alias="QGroundControl/Controls/CameraSection.qml">src/PlanView/CameraSection.qml</file>
         <file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc
index 294f856..171f20b 100644
--- a/src/Joystick/Joystick.cc
+++ b/src/Joystick/Joystick.cc
@@ -684,11 +684,9 @@ QString Joystick::getButtonAction(int button)
 QVariantList Joystick::buttonActions(void)
 {
     QVariantList list;
-
     for (int button=0; button<_totalButtonCount; button++) {
         list += QVariant::fromValue(_rgButtonActions[button]);
     }
-
     return list;
 }
 
@@ -703,13 +701,10 @@ void Joystick::setThrottleMode(int mode)
         qCWarning(JoystickLog) << "Invalid throttle mode" << mode;
         return;
     }
-
-    _throttleMode = (ThrottleMode_t)mode;
-
+    _throttleMode = static_cast<ThrottleMode_t>(mode);
     if (_throttleMode == ThrottleModeDownZero) {
         setAccumulator(false);
     }
-
     _saveSettings();
     emit throttleModeChanged(_throttleMode);
 }
@@ -725,7 +720,6 @@ void Joystick::setNegativeThrust(bool allowNegative)
         return;
     }
     _negativeThrust = allowNegative;
-
     _saveSettings();
     emit negativeThrustChanged(_negativeThrust);
 }
@@ -738,7 +732,6 @@ float Joystick::exponential(void)
 void Joystick::setExponential(float expo)
 {
     _exponential = expo;
-
     _saveSettings();
     emit exponentialChanged(_exponential);
 }
@@ -751,7 +744,6 @@ bool Joystick::accumulator(void)
 void Joystick::setAccumulator(bool accu)
 {
     _accumulator = accu;
-
     _saveSettings();
     emit accumulatorChanged(_accumulator);
 }
@@ -764,7 +756,6 @@ bool Joystick::deadband(void)
 void Joystick::setDeadband(bool deadband)
 {
     _deadband = deadband;
-
     _saveSettings();
 }
 
@@ -776,7 +767,6 @@ bool Joystick::circleCorrection(void)
 void Joystick::setCircleCorrection(bool circleCorrection)
 {
     _circleCorrection = circleCorrection;
-
     _saveSettings();
     emit circleCorrectionChanged(_circleCorrection);
 }
@@ -799,7 +789,6 @@ void Joystick::setFrequency(float val)
 void Joystick::setCalibrationMode(bool calibrating)
 {
     _calibrationMode = calibrating;
-
     if (calibrating && !isRunning()) {
         _pollingStartedForCalibration = true;
         startPolling(_multiVehicleManager->activeVehicle());
@@ -815,7 +804,6 @@ void Joystick::_buttonAction(const QString& action)
     if (!_activeVehicle || !_activeVehicle->joystickEnabled()) {
         return;
     }
-
     if (action == _buttonActionArm) {
         _activeVehicle->setArmed(true);
     } else if (action == _buttonActionDisarm) {
diff --git a/src/QmlControls/AxisMonitor.qml b/src/QmlControls/AxisMonitor.qml
new file mode 100644
index 0000000..ec4cb7b
--- /dev/null
+++ b/src/QmlControls/AxisMonitor.qml
@@ -0,0 +1,90 @@
+import QtQuick                      2.11
+import QtQuick.Controls             2.4
+
+import QGroundControl               1.0
+import QGroundControl.Palette       1.0
+import QGroundControl.Controls      1.0
+import QGroundControl.ScreenTools   1.0
+
+Item {
+    property int    axisValue:          0
+    property int    deadbandValue:      0
+    property bool   narrowIndicator:    false
+    property color  deadbandColor:      "#8c161a"
+    property bool   mapped:             false
+    property bool   reversed:           false
+
+    property color  __barColor:         qgcPal.windowShade
+
+    // Bar
+    Rectangle {
+        id:                     bar
+        anchors.verticalCenter: parent.verticalCenter
+        width:                  parent.width
+        height:                 parent.height / 2
+        color:                  __barColor
+    }
+
+    // Deadband
+    Rectangle {
+        id:                     deadbandBar
+        anchors.verticalCenter: parent.verticalCenter
+        x:                      _deadbandPosition
+        width:                  _deadbandWidth
+        height:                 parent.height / 2
+        color:                  deadbandColor
+        visible:                controller.deadbandToggle
+
+        property real _percentDeadband:     ((2 * deadbandValue) / (32768.0 * 2))
+        property real _deadbandWidth:       parent.width * _percentDeadband
+        property real _deadbandPosition:    (parent.width - _deadbandWidth) / 2
+    }
+
+    // Center point
+    Rectangle {
+        anchors.horizontalCenter:   parent.horizontalCenter
+        width:                      ScreenTools.defaultFontPixelWidth / 2
+        height:                     parent.height
+        color:                      qgcPal.window
+    }
+
+    // Indicator
+    Rectangle {
+        anchors.verticalCenter: parent.verticalCenter
+        width:                  parent.narrowIndicator ?  height/6 : height
+        height:                 parent.height * 0.75
+        x:                      (reversed ? (parent.width - _indicatorPosition) : _indicatorPosition) - (width / 2)
+        radius:                 width / 2
+        color:                  qgcPal.text
+        visible:                mapped
+
+        property real _percentAxisValue:    ((axisValue + 32768.0) / (32768.0 * 2))
+        property real _indicatorPosition:   parent.width * _percentAxisValue
+    }
+
+    QGCLabel {
+        anchors.fill:           parent
+        horizontalAlignment:    Text.AlignHCenter
+        verticalAlignment:      Text.AlignVCenter
+        text:                   qsTr("Not Mapped")
+        visible:                !mapped
+    }
+
+    ColorAnimation {
+        id:         barAnimation
+        target:     bar
+        property:   "color"
+        from:       "yellow"
+        to:         __barColor
+        duration:   1500
+    }
+
+    // Axis value debugger
+    /*
+    QGCLabel {
+        anchors.fill: parent
+        text: axisValue
+    }
+    */
+
+}
diff --git a/src/QmlControls/QGroundControl/Controls/qmldir b/src/QmlControls/QGroundControl/Controls/qmldir
index 6fe4e3c..2d079c6 100644
--- a/src/QmlControls/QGroundControl/Controls/qmldir
+++ b/src/QmlControls/QGroundControl/Controls/qmldir
@@ -2,6 +2,7 @@ Module QGroundControl.Controls
 
 AnalyzePage             1.0 AnalyzePage.qml
 AppMessages             1.0 AppMessages.qml
+AxisMonitor             1.0 AxisMonitor.qml
 CameraCalc              1.0 CameraCalc.qml
 APMSubMotorDisplay      1.0 APMSubMotorDisplay.qml
 CameraSection           1.0 CameraSection.qml
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 008fbbd..eb6505b 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -2741,11 +2741,18 @@ void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
     }
 }
 
-void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
+void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust, double gimbalPitch, double gimbalYaw)
 {
     // The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
     if ( !_joystickEnabled && !_highLatencyLink) {
-        _uas->setExternalControlSetpoint(roll, pitch, yaw, thrust, 0, JoystickModeRC);
+        _uas->setExternalControlSetpoint(
+            static_cast<float>(roll),
+            static_cast<float>(pitch),
+            static_cast<float>(yaw),
+            static_cast<float>(thrust),
+            static_cast<float>(gimbalPitch),
+            static_cast<float>(gimbalYaw),
+            0, JoystickModeRC);
     }
 }
 
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 0b6aea3..acf3902 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -697,7 +697,7 @@ public:
     // Called when the message drop-down is invoked to clear current count
     Q_INVOKABLE void        resetMessages();
 
-    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
+    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust, double gimbalPitch = 0, double gimbalYaw = 0);
     Q_INVOKABLE void disconnectInactiveVehicle(void);
 
     /// Command vehicle to return to launch
diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/VehicleSetup/JoystickConfig.qml
index ab247af..c141ab4 100644
--- a/src/VehicleSetup/JoystickConfig.qml
+++ b/src/VehicleSetup/JoystickConfig.qml
@@ -8,9 +8,10 @@
  ****************************************************************************/
 
 
-import QtQuick          2.3
-import QtQuick.Controls 1.2
-import QtQuick.Dialogs  1.2
+import QtQuick                      2.11
+import QtQuick.Controls             2.4
+import QtQuick.Dialogs              1.3
+import QtQuick.Layouts              1.11
 
 import QGroundControl               1.0
 import QGroundControl.Palette       1.0
@@ -25,7 +26,7 @@ SetupPage {
     id:                 joystickPage
     pageComponent:      pageComponent
     pageName:           qsTr("Joystick")
-    pageDescription:    qsTr("Joystick Setup is used to configure a calibrate joysticks.")
+    pageDescription:    "" // qsTr("Joystick Setup is used to configure and calibrate joysticks.")
 
     readonly property real  _maxButtons:         64
     readonly property real  _attitudeLabelWidth: ScreenTools.defaultFontPixelWidth * 12
@@ -43,8 +44,8 @@ SetupPage {
     Component {
         id: pageComponent
         Item {
-            width:      availableWidth
-            height:     mainColumn.height
+            width:  availableWidth
+            height: bar.height + joyLoader.height
 
             readonly property real  labelToMonitorMargin:   ScreenTools.defaultFontPixelWidth * 3
             property var            _activeJoystick:        joystickManager.activeJoystick
@@ -55,996 +56,36 @@ SetupPage {
 
             JoystickConfigController {
                 id:             controller
-                cancelButton:   cancelButton
-                nextButton:     nextButton
-                skipButton:     skipButton
             }
 
-            // Main view
-            Column {
-                id:                     mainColumn
-                spacing:                ScreenTools.defaultFontPixelHeight
-                anchors.right:          parent.right
-                anchors.left:           parent.left
-                anchors.margins:        ScreenTools.defaultFontPixelWidth
-                Row {
-                    spacing:            ScreenTools.defaultFontPixelWidth * 2
-                    QGCCheckBox {
-                        id:                 enabledCheckBox
-                        enabled:            _activeJoystick ? _activeJoystick.calibrated : false
-                        text:               _activeJoystick ? _activeJoystick.calibrated ? qsTr("Enable joystick input") : qsTr("Enable not allowed (Calibrate First)") : ""
-                        anchors.verticalCenter: parent.verticalCenter
-                        onClicked:          activeVehicle.joystickEnabled = checked
-                        Component.onCompleted: {
-                            checked = activeVehicle.joystickEnabled
-                        }
-                        Connections {
-                            target: activeVehicle
-                            onJoystickEnabledChanged: {
-                                enabledCheckBox.checked = activeVehicle.joystickEnabled
-                            }
-                        }
-                        Connections {
-                            target: joystickManager
-                            onActiveJoystickChanged: {
-                                if(_activeJoystick) {
-                                    enabledCheckBox.checked = Qt.binding(function() { return _activeJoystick.calibrated && activeVehicle.joystickEnabled })
-                                }
-                            }
-                        }
-                    }
-                    QGCLabel {
-                        text:           qsTr("Active joystick:")
-                        anchors.verticalCenter: parent.verticalCenter
-                    }
-                    QGCComboBox {
-                        id:             joystickCombo
-                        width:          ScreenTools.defaultFontPixelWidth * 40
-                        anchors.verticalCenter: parent.verticalCenter
-                        model:          joystickManager.joystickNames
-                        onActivated:    joystickManager.activeJoystickName = textAt(index)
-                        Component.onCompleted: {
-                            var index = joystickCombo.find(joystickManager.activeJoystickName)
-                            if (index === -1) {
-                                console.warn(qsTr("Active joystick name not in combo"), joystickManager.activeJoystickName)
-                            } else {
-                                joystickCombo.currentIndex = index
-                            }
-                        }
-                        Connections {
-                            target: joystickManager
-                            onAvailableJoysticksChanged: {
-                                var index = joystickCombo.find(joystickManager.activeJoystickName)
-                                if (index >= 0) {
-                                    joystickCombo.currentIndex = index
-                                }
-                            }
-                        }
-                    }
+            TabBar {
+                id:             bar
+                width:          parent.width
+                anchors.top:    parent.top
+                TabButton {
+                    text:       qsTr("General")
                 }
-                //-- Separator
-                Rectangle {
-                    width:          parent.width
-                    height:         1
-                    border.color:   qgcPal.text
-                    border.width:   1
+                TabButton {
+                    text:       qsTr("Button Assigment")
                 }
-                //-- Main Row
-                Row {
-                    spacing:                    ScreenTools.defaultFontPixelWidth
-                    anchors.horizontalCenter:   parent.horizontalCenter
-                    // Left side column
-                    Column {
-                        id:                     leftColumn
-                        spacing:                ScreenTools.defaultFontPixelHeight
-
-                        // Attitude Controls
-                        Column {
-                            width:      parent.width
-                            spacing:    5
-
-                            QGCLabel { text: qsTr("Attitude Controls") }
-
-                            Item {
-                                width:                  parent.width
-                                height:                 defaultTextHeight * 2
-
-                                QGCLabel {
-                                    id:                 rollLabel
-                                    width:              _attitudeLabelWidth
-                                    text:               activeVehicle.sub ? qsTr("Lateral") : qsTr("Roll")
-                                }
-
-                                Loader {
-                                    id:                 rollLoader
-                                    anchors.left:       rollLabel.right
-                                    anchors.right:      parent.right
-                                    height:             ScreenTools.defaultFontPixelHeight
-                                    width:              100
-                                    sourceComponent:    axisMonitorDisplayComponent
-                                    property bool mapped:   controller.rollAxisMapped
-                                    property bool reversed: controller.rollAxisReversed
-                                }
-
-                                Connections {
-                                    target:             _activeJoystick
-                                    onManualControl:    rollLoader.item.axisValue = roll*32768.0
-                                }
-                            }
-
-                            Item {
-                                width:                  parent.width
-                                height:                 defaultTextHeight * 2
-
-                                QGCLabel {
-                                    id:                 pitchLabel
-                                    width:              _attitudeLabelWidth
-                                    text:               activeVehicle.sub ? qsTr("Forward") : qsTr("Pitch")
-                                }
-
-                                Loader {
-                                    id:                 pitchLoader
-                                    anchors.left:       pitchLabel.right
-                                    anchors.right:      parent.right
-                                    height:             ScreenTools.defaultFontPixelHeight
-                                    width:              100
-                                    sourceComponent:    axisMonitorDisplayComponent
-                                    property bool mapped:   controller.pitchAxisMapped
-                                    property bool reversed: controller.pitchAxisReversed
-                                }
-
-                                Connections {
-                                    target:             _activeJoystick
-                                    onManualControl:    pitchLoader.item.axisValue = pitch*32768.0
-                                }
-                            }
-
-                            Item {
-                                width:                  parent.width
-                                height:                 defaultTextHeight * 2
-
-                                QGCLabel {
-                                    id:                 yawLabel
-                                    width:              _attitudeLabelWidth
-                                    text:               qsTr("Yaw")
-                                }
-
-                                Loader {
-                                    id:                 yawLoader
-                                    anchors.left:       yawLabel.right
-                                    anchors.right:      parent.right
-                                    height:             ScreenTools.defaultFontPixelHeight
-                                    width:              100
-                                    sourceComponent:    axisMonitorDisplayComponent
-                                    property bool mapped:   controller.yawAxisMapped
-                                    property bool reversed: controller.yawAxisReversed
-                                }
-
-                                Connections {
-                                    target:             _activeJoystick
-                                    onManualControl:    yawLoader.item.axisValue = yaw*32768.0
-                                }
-                            }
-
-                            Item {
-                                width:                  parent.width
-                                height:                 defaultTextHeight * 2
-
-                                QGCLabel {
-                                    id:                 throttleLabel
-                                    width:              _attitudeLabelWidth
-                                    text:               qsTr("Throttle")
-                                }
-
-                                Loader {
-                                    id:                 throttleLoader
-                                    anchors.left:       throttleLabel.right
-                                    anchors.right:      parent.right
-                                    height:             ScreenTools.defaultFontPixelHeight
-                                    width:              100
-                                    sourceComponent:    axisMonitorDisplayComponent
-                                    property bool mapped:   controller.throttleAxisMapped
-                                    property bool reversed: controller.throttleAxisReversed
-                                }
-
-                                Connections {
-                                    target:             _activeJoystick
-                                    onManualControl:    throttleLoader.item.axisValue = _activeJoystick.negativeThrust ? -throttle*32768.0 : (-2*throttle+1)*32768.0
-                                }
-                            }
-
-                            Item {
-                                width:                  parent.width
-                                height:                 controller.hasGimbal ? defaultTextHeight * 2 : 0
-                                visible:                controller.hasGimbal
-
-                                QGCLabel {
-                                    id:                 gimbalPitchLabel
-                                    width:              _attitudeLabelWidth
-                                    text:               qsTr("Gimbal Pitch")
-                                }
-
-                                Loader {
-                                    id:                 gimbalPitchLoader
-                                    anchors.left:       gimbalPitchLabel.right
-                                    anchors.right:      parent.right
-                                    height:             ScreenTools.defaultFontPixelHeight
-                                    width:              100
-                                    sourceComponent:    axisMonitorDisplayComponent
-                                    property bool mapped:   controller.gimbalPitchAxisMapped
-                                    property bool reversed: controller.gimbalPitchAxisReversed
-                                }
-
-                                Connections {
-                                    target:             _activeJoystick
-                                    onManualControl:    gimbalPitchLoader.item.axisValue = gimbalPitch * 32768.0
-                                }
-                            }
-
-                            Item {
-                                width:                  parent.width
-                                height:                 controller.hasGimbal ? defaultTextHeight * 2 : 0
-                                visible:                controller.hasGimbal
-
-                                QGCLabel {
-                                    id:                 gimbalYawLabel
-                                    width:              _attitudeLabelWidth
-                                    text:               qsTr("Gimbal Yaw")
-                                }
-
-                                Loader {
-                                    id:                 gimbalYawLoader
-                                    anchors.left:       gimbalYawLabel.right
-                                    anchors.right:      parent.right
-                                    height:             ScreenTools.defaultFontPixelHeight
-                                    width:              100
-                                    sourceComponent:    axisMonitorDisplayComponent
-                                    property bool mapped:   controller.gimbalYawAxisMapped
-                                    property bool reversed: controller.gimbalYawAxisReversed
-                                }
-
-                                Connections {
-                                    target:             _activeJoystick
-                                    onManualControl:    gimbalYawLoader.item.axisValue = gimbalYaw * 32768.0
-                                }
-                            }
-
-                        } // Column - Attitude Control labels
-
-                        // Command Buttons
-                        Row {
-                            spacing: 10
-                            visible: _activeJoystick.requiresCalibration
-                            anchors.horizontalCenter: parent.horizontalCenter
-                            QGCButton {
-                                id:         skipButton
-                                text:       qsTr("Skip")
-                                width:      ScreenTools.defaultFontPixelWidth * 10
-                                onClicked:  controller.skipButtonClicked()
-                            }
-                            QGCButton {
-                                id:         cancelButton
-                                text:       qsTr("Cancel")
-                                width:      ScreenTools.defaultFontPixelWidth * 10
-                                onClicked:  controller.cancelButtonClicked()
-                            }
-                            QGCButton {
-                                id:         nextButton
-                                primary:    true
-                                text:       qsTr("Calibrate")
-                                width:      ScreenTools.defaultFontPixelWidth * 10
-                                onClicked:  controller.nextButtonClicked()
-                            }
-                        }
-
-                        // Status Text
-                        QGCLabel {
-                            text:           controller.statusText
-                            width:          parent.width
-                            wrapMode:       Text.WordWrap
-                            visible:        text !== ""
-                        }
-
-                        //-- Separator
-                        Rectangle {
-                            width:          parent.width
-                            height:         1
-                            border.color:   qgcPal.text
-                            border.width:   1
-                        }
-
-                        // Settings
-                        Row {
-                            width:      parent.width
-                            spacing:    ScreenTools.defaultFontPixelWidth
-
-                            // Left column settings
-                            Column {
-                                width:      parent.width * 0.5
-                                spacing:    ScreenTools.defaultFontPixelHeight
-
-                                QGCLabel { text: qsTr("Additional Joystick settings:") }
-
-                                Column {
-                                    width:      parent.width
-                                    spacing:    ScreenTools.defaultFontPixelHeight
-
-                                    Column {
-                                        spacing: ScreenTools.defaultFontPixelHeight / 3
-                                        visible: activeVehicle.supportsThrottleModeCenterZero
-
-                                        QGCRadioButton {
-                                            text:           qsTr("Center stick is zero throttle")
-                                            checked:        _activeJoystick ? _activeJoystick.throttleMode === 0 : false
-
-                                            onClicked: _activeJoystick.throttleMode = 0
-                                        }
-
-                                        Row {
-                                            x:          20
-                                            width:      parent.width
-                                            spacing:    ScreenTools.defaultFontPixelWidth
-                                            visible:    _activeJoystick ? _activeJoystick.throttleMode === 0 : false
-
-                                            QGCCheckBox {
-                                                id:         accumulator
-                                                checked:    _activeJoystick ? _activeJoystick.accumulator : false
-                                                text:       qsTr("Spring loaded throttle smoothing")
-
-                                                onClicked:  _activeJoystick.accumulator = checked
-                                            }
-                                        }
-
-                                        QGCRadioButton {
-                                            text:           qsTr("Full down stick is zero throttle")
-                                            checked:        _activeJoystick ? _activeJoystick.throttleMode === 1 : false
-
-                                            onClicked: _activeJoystick.throttleMode = 1
-                                        }
-
-                                        QGCCheckBox {
-                                            visible:        activeVehicle.supportsNegativeThrust
-                                            id:             negativeThrust
-                                            text:           qsTr("Allow negative Thrust")
-                                            enabled:        _activeJoystick.negativeThrust = activeVehicle.supportsNegativeThrust
-                                            checked:        _activeJoystick ? _activeJoystick.negativeThrust : false
-                                            onClicked:      _activeJoystick.negativeThrust = checked
-                                        }
-                                    }
-
-                                    Column {
-                                        spacing: ScreenTools.defaultFontPixelHeight
-
-                                        QGCLabel {
-                                            id:                 expoSliderLabel
-                                            text:               qsTr("Exponential:")
-                                        }
-
-                                        Row {
-                                            spacing:            ScreenTools.defaultFontPixelWidth
-                                            QGCSlider {
-                                                id:             expoSlider
-                                                width:          ScreenTools.defaultFontPixelWidth * 14
-                                                minimumValue:   0
-                                                maximumValue:   0.75
-                                                Component.onCompleted: value = -_activeJoystick.exponential
-                                                onValueChanged: _activeJoystick.exponential = -value
-                                             }
-                                            QGCLabel {
-                                                id:     expoSliderIndicator
-                                                text:   expoSlider.value.toFixed(2)
-                                            }
-                                        }
-                                    }
-
-                                    QGCCheckBox {
-                                        id:         advancedSettings
-                                        checked:    activeVehicle.joystickMode !== 0
-                                        text:       qsTr("Advanced settings (careful!)")
-
-                                        onClicked: {
-                                            if (!checked) {
-                                                activeVehicle.joystickMode = 0
-                                            }
-                                        }
-                                    }
-
-                                    Row {
-                                        width:      parent.width
-                                        spacing:    ScreenTools.defaultFontPixelWidth
-                                        visible:    advancedSettings.checked
-
-                                        QGCLabel {
-                                            id:                 joystickModeLabel
-                                            anchors.baseline:   joystickModeCombo.baseline
-                                            text:               qsTr("Joystick mode:")
-                                        }
-
-                                        QGCComboBox {
-                                            id:             joystickModeCombo
-                                            currentIndex:   activeVehicle.joystickMode
-                                            width:          ScreenTools.defaultFontPixelWidth * 20
-                                            model:          activeVehicle.joystickModes
-
-                                            onActivated: activeVehicle.joystickMode = index
-                                        }
-                                    }
-
-                                    Row {
-                                        width:      parent.width
-                                        spacing:    ScreenTools.defaultFontPixelWidth
-                                        visible:    advancedSettings.checked
-                                        QGCLabel {
-                                            text:       qsTr("Message frequency (Hz):")
-                                            anchors.verticalCenter: parent.verticalCenter
-                                        }
-                                        QGCTextField {
-                                            text:       _activeJoystick.frequency
-                                            validator:  DoubleValidator { bottom: 0.25; top: 100.0; }
-                                            inputMethodHints: Qt.ImhFormattedNumbersOnly
-                                            onEditingFinished: {
-                                                _activeJoystick.frequency = parseFloat(text)
-                                            }
-                                        }
-                                    }
-
-                                    Row {
-                                        width:      parent.width
-                                        spacing:    ScreenTools.defaultFontPixelWidth
-                                        visible:    advancedSettings.checked
-                                        QGCCheckBox {
-                                            id:         joystickCircleCorrection
-                                            checked:    activeVehicle.joystickMode !== 0
-                                            text:       qsTr("Enable circle correction")
-
-                                            Component.onCompleted: checked = _activeJoystick.circleCorrection
-                                            onClicked: {
-                                                _activeJoystick.circleCorrection = checked
-                                            }
-                                        }
-                                    }
-
-                                    Row {
-                                        width:      parent.width
-                                        spacing:    ScreenTools.defaultFontPixelWidth
-                                        visible:    advancedSettings.checked
-
-                                        QGCCheckBox {
-                                            id:         deadband
-                                            checked:    controller.deadbandToggle
-                                            text:       qsTr("Deadbands")
-
-                                            onClicked:  controller.deadbandToggle = checked
-                                        }
-                                    }
-                                    Row{
-                                        width: parent.width
-                                        spacing: ScreenTools.defaultFontPixelWidth
-                                        visible: advancedSettings.checked
-                                        QGCLabel{
-                                            width:       parent.width * 0.85
-                                            font.pointSize:     ScreenTools.smallFontPointSize
-                                            wrapMode:           Text.WordWrap
-                                            text:   qsTr("Deadband can be set during the first ") +
-                                                    qsTr("step of calibration by gently wiggling each axis. ") +
-                                                    qsTr("Deadband can also be adjusted by clicking and ") +
-                                                    qsTr("dragging vertically on the corresponding axis monitor.")
-                                            visible: controller.deadbandToggle
-                                        }
-                                    }
-                                }
-                            } // Column - left column
-
-                            // Right column settings
-                            Column {
-                                width:      parent.width / 2
-                                spacing:    ScreenTools.defaultFontPixelHeight
-
-                                Connections {
-                                    target: _activeJoystick
-
-                                    onRawButtonPressedChanged: {
-                                        if (buttonActionRepeater.itemAt(index)) {
-                                            buttonActionRepeater.itemAt(index).pressed = pressed
-                                        }
-                                        if (jsButtonActionRepeater.itemAt(index)) {
-                                            jsButtonActionRepeater.itemAt(index).pressed = pressed
-                                        }
-                                    }
-                                }
-                                //-- AP_JSButton Buttons (ArduSub)
-                                QGCLabel { text: qsTr("Button actions:"); visible: activeVehicle.supportsJSButton; }
-                                Column {
-                                    width:      parent.width
-                                    visible:    activeVehicle.supportsJSButton
-                                    spacing:    ScreenTools.defaultFontPixelHeight / 3
-                                    Row {
-                                        spacing: ScreenTools.defaultFontPixelWidth
-                                        QGCLabel {
-                                            horizontalAlignment:    Text.AlignHCenter
-                                            width:                  ScreenTools.defaultFontPixelHeight * 1.5
-                                            text:                   qsTr("#")
-                                        }
-                                        QGCLabel {
-                                            width:                  ScreenTools.defaultFontPixelWidth * 15
-                                            text:                   qsTr("Function: ")
-                                        }
-                                        QGCLabel {
-                                            width:                  ScreenTools.defaultFontPixelWidth * 15
-                                            text:                   qsTr("Shift Function: ")
-                                        }
-                                    } // Row
-                                    Repeater {
-                                        id:     jsButtonActionRepeater
-                                        model:  _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : 0
-
-                                        Row {
-                                            spacing: ScreenTools.defaultFontPixelWidth
-                                            visible: activeVehicle.supportsJSButton
-
-                                            property bool pressed
-
-                                            Rectangle {
-                                                anchors.verticalCenter:     parent.verticalCenter
-                                                width:                      ScreenTools.defaultFontPixelHeight * 1.5
-                                                height:                     width
-                                                border.width:               1
-                                                border.color:               qgcPal.text
-                                                color:                      pressed ? qgcPal.buttonHighlight : qgcPal.button
-
-
-                                                QGCLabel {
-                                                    anchors.fill:           parent
-                                                    color:                  pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
-                                                    horizontalAlignment:    Text.AlignHCenter
-                                                    verticalAlignment:      Text.AlignVCenter
-                                                    text:                   modelData
-                                                }
-                                            }
-
-                                            FactComboBox {
-                                                id:         mainJSButtonActionCombo
-                                                width:      ScreenTools.defaultFontPixelWidth * 15
-                                                fact:       controller.parameterExists(-1, "BTN"+index+"_FUNCTION") ? controller.getParameterFact(-1, "BTN" + index + "_FUNCTION") : null;
-                                                indexModel: false
-                                            }
-
-                                            FactComboBox {
-                                                id:         shiftJSButtonActionCombo
-                                                width:      ScreenTools.defaultFontPixelWidth * 15
-                                                fact:       controller.parameterExists(-1, "BTN"+index+"_SFUNCTION") ? controller.getParameterFact(-1, "BTN" + index + "_SFUNCTION") : null;
-                                                indexModel: false
-                                            }
-                                        } // Row
-                                    } // Repeater
-                                } // Column
-                            } // Column - right setting column
-                        } // Row - Settings
-
-                    } // Column - Left Main Column
-                    // Right side column
-                    Column {
-                        width:          Math.min(ScreenTools.defaultFontPixelWidth * 35, availableWidth * 0.4)
-                        spacing:        ScreenTools.defaultFontPixelHeight
-
-                        Row {
-                            spacing: ScreenTools.defaultFontPixelWidth
-                            anchors.horizontalCenter: parent.horizontalCenter
-
-                            QGCLabel {
-                                text: "TX Mode:"
-                                anchors.verticalCenter: parent.verticalCenter
-                            }
-
-                            QGCRadioButton {
-                                text:       "1"
-                                checked:    controller.transmitterMode == 1
-                                enabled:    !controller.calibrating
-                                onClicked:  controller.transmitterMode = 1
-                                anchors.verticalCenter: parent.verticalCenter
-                            }
-
-                            QGCRadioButton {
-                                text:       "2"
-                                checked:    controller.transmitterMode == 2
-                                enabled:    !controller.calibrating
-                                onClicked:  controller.transmitterMode = 2
-                                anchors.verticalCenter: parent.verticalCenter
-                            }
-
-                            QGCRadioButton {
-                                text:       "3"
-                                checked:    controller.transmitterMode == 3
-                                enabled:    !controller.calibrating
-                                onClicked:  controller.transmitterMode = 3
-                                anchors.verticalCenter: parent.verticalCenter
-                            }
-
-                            QGCRadioButton {
-                                text:       "4"
-                                checked:    controller.transmitterMode == 4
-                                enabled:    !controller.calibrating
-                                onClicked:  controller.transmitterMode = 4
-                                anchors.verticalCenter: parent.verticalCenter
-                            }
-                        }
-
-                        //-------------------------------------------------------------
-                        //-- Joystick Icon
-                        Rectangle {
-                            width:      Math.round(parent.width * 0.9)
-                            height:     Math.round(width * 0.5)
-                            radius:     ScreenTools.defaultFontPixelWidth * 2
-                            color:      qgcPal.window
-                            border.color: qgcPal.text
-                            border.width: ScreenTools.defaultFontPixelWidth * 0.25
-                            anchors.horizontalCenter: parent.horizontalCenter
-                            property bool hasStickPositions: controller.stickPositions.length === 4
-                            Connections {
-                                target:     controller
-                                onStickPositionsChanged: {
-                                    console.log(controller.stickPositions[0] + ' ' + controller.stickPositions[1] + ' ' + controller.stickPositions[2] + ' ' + controller.stickPositions[3])
-                                }
-                            }
-
-                            //---------------------------------------------------------
-                            //-- Left Stick
-                            Rectangle {
-                                width:      parent.width * 0.25
-                                height:     width
-                                radius:     width * 0.5
-                                color:      qgcPal.window
-                                border.color: qgcPal.text
-                                border.width: ScreenTools.defaultFontPixelWidth * 0.125
-                                x:          (parent.width  * 0.25) - (width  * 0.5)
-                                y:          (parent.height * 0.5)  - (height * 0.5)
-                            }
-                            Rectangle {
-                                color:  qgcPal.colorGreen
-                                width:  parent.width * 0.035
-                                height: width
-                                radius: width * 0.5
-                                visible: parent.hasStickPositions
-                                x:      (parent.width  * controller.stickPositions[0]) - (width  * 0.5)
-                                y:      (parent.height * controller.stickPositions[1]) - (height * 0.5)
-                            }
-                            //---------------------------------------------------------
-                            //-- Right Stick
-                            Rectangle {
-                                width:      parent.width * 0.25
-                                height:     width
-                                radius:     width * 0.5
-                                color:      qgcPal.window
-                                border.color: qgcPal.text
-                                border.width: ScreenTools.defaultFontPixelWidth * 0.125
-                                x:          (parent.width  * 0.75) - (width  * 0.5)
-                                y:          (parent.height * 0.5)  - (height * 0.5)
-                            }
-                            Rectangle {
-                                color:  qgcPal.colorGreen
-                                width:  parent.width * 0.035
-                                height: width
-                                radius: width * 0.5
-                                visible: parent.hasStickPositions
-                                x:      (parent.width  * controller.stickPositions[2]) - (width  * 0.5)
-                                y:      (parent.height * controller.stickPositions[3]) - (height * 0.5)
-                            }
-                            //---------------------------------------------------------
-                            //-- Gimbal Pitch
-                            Rectangle {
-                                width:      ScreenTools.defaultFontPixelWidth * 0.125
-                                height:     parent.height * 0.2
-                                color:      qgcPal.text
-                                visible:    controller.hasGimbal
-                                x:          (parent.width  * 0.5) - (width  * 0.5)
-                                y:          (parent.height * 0.5) - (height * 0.5)
-                            }
-                            Rectangle {
-                                color:      qgcPal.colorGreen
-                                width:      parent.width * 0.035
-                                height:     width
-                                radius:     width * 0.5
-                                visible:    controller.hasGimbal
-                                x:          (parent.width  * controller.gimbalPositions[0]) - (width  * 0.5)
-                                y:          (parent.height * controller.gimbalPositions[1]) - (height * 0.5)
-                            }
-                            //---------------------------------------------------------
-                            //-- Gimbal Yaw
-                            Rectangle {
-                                width:      parent.width * 0.2
-                                height:     ScreenTools.defaultFontPixelWidth * 0.125
-                                color:      qgcPal.text
-                                visible:    controller.hasGimbal
-                                x:          (parent.width  * 0.5) - (width  * 0.5)
-                                y:          (parent.height * 0.3) - (height * 0.5)
-                            }
-                            Rectangle {
-                                color:      qgcPal.colorGreen
-                                width:      parent.width * 0.035
-                                height:     width
-                                radius:     width * 0.5
-                                visible:    controller.hasGimbal
-                                x:          (parent.width  * controller.gimbalPositions[2]) - (width  * 0.5)
-                                y:          (parent.height * controller.gimbalPositions[3]) - (height * 0.5)
-                            }
-                        }
-
-                        // Axis monitor
-                        Column {
-                            width:      parent.width
-                            spacing:    5
-
-                            QGCLabel {
-                                text: qsTr("Axis Monitor")
-                                anchors.horizontalCenter: parent.horizontalCenter
-                            }
-
-                            Connections {
-                                target: controller
-
-                                onAxisValueChanged: {
-                                    if (axisMonitorRepeater.itemAt(axis)) {
-                                        axisMonitorRepeater.itemAt(axis).loader.item.axisValue = value
-                                    }
-                                }
-
-                                onAxisDeadbandChanged: {
-                                    if (axisMonitorRepeater.itemAt(axis)) {
-                                        axisMonitorRepeater.itemAt(axis).loader.item.deadbandValue = value
-                                    }
-                                }
-                            }
-
-                            Repeater {
-                                id:     axisMonitorRepeater
-                                model:  _activeJoystick ? _activeJoystick.axisCount : 0
-                                width:  parent.width
-
-                                Row {
-                                    spacing:    5
-                                    anchors.horizontalCenter: parent.horizontalCenter
-
-                                    // Need this to get to loader from Connections above
-                                    property Item loader: theLoader
-
-                                    QGCLabel {
-                                        id:     axisLabel
-                                        text:   modelData
-                                    }
-
-                                    Loader {
-                                        id:                     theLoader
-                                        anchors.verticalCenter: axisLabel.verticalCenter
-                                        height:                 ScreenTools.defaultFontPixelHeight
-                                        width:                  200
-                                        sourceComponent:        axisMonitorDisplayComponent
-                                        Component.onCompleted:  item.narrowIndicator = true
-
-                                        property bool mapped:               true
-                                        readonly property bool reversed:    false
-
-                                        MouseArea {
-                                            id:                 deadbandMouseArea
-                                            anchors.fill:       parent.item
-                                            enabled:            controller.deadbandToggle
-                                            preventStealing:    true
-
-                                            property real startX
-                                            property real direction
-
-                                            onPressed: {
-                                                startX = mouseX
-                                                direction = startX > width/2 ? 1 : -1
-                                                parent.item.deadbandColor = "#3C6315"
-                                            }
-                                            onPositionChanged: {
-                                                var mouseToDeadband = 32768/(width/2) // Factor to have deadband follow the mouse movement
-                                                var newValue = parent.item.deadbandValue + direction*(mouseX - startX)*mouseToDeadband
-                                                if ((newValue > 0) && (newValue <32768)){parent.item.deadbandValue=newValue;}
-                                                startX = mouseX
-                                            }
-                                            onReleased: {
-                                                controller.setDeadbandValue(modelData,parent.item.deadbandValue)
-                                                parent.item.deadbandColor = "#8c161a"
-                                            }
-                                        }
-                                    }
-
-                                }
-                            }
-                        } // Column - Axis Monitor
-
-                        // Button monitor
-                        Column {
-                            width:      parent.width
-                            spacing:    ScreenTools.defaultFontPixelHeight
-
-                            QGCLabel {
-                                text: qsTr("Button Monitor")
-                                anchors.horizontalCenter: parent.horizontalCenter
-                            }
-
-                            Connections {
-                                target: _activeJoystick
-
-                                onRawButtonPressedChanged: {
-                                    if (buttonMonitorRepeater.itemAt(index)) {
-                                        buttonMonitorRepeater.itemAt(index).pressed = pressed
-                                    }
-                                }
-                            }
-
-                            Flow {
-                                width:      parent.width * 0.9
-                                spacing:    -1
-                                anchors.horizontalCenter: parent.horizontalCenter
-
-                                Repeater {
-                                    id:     buttonMonitorRepeater
-                                    model:  _activeJoystick ? _activeJoystick.totalButtonCount : 0
-
-                                    Rectangle {
-                                        width:          ScreenTools.defaultFontPixelHeight * 1.5
-                                        height:         width
-                                        border.width:   1
-                                        border.color:   qgcPal.text
-                                        color:          pressed ? qgcPal.buttonHighlight : qgcPal.windowShade
-
-                                        property bool pressed
-
-                                        QGCLabel {
-                                            anchors.fill:           parent
-                                            color:                  pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
-                                            horizontalAlignment:    Text.AlignHCenter
-                                            verticalAlignment:      Text.AlignVCenter
-                                            text:                   modelData
-                                        }
-                                    }
-                                } // Repeater
-                            } // Row
-                        } // Column - Axis Monitor
-                    } // Column - Right Column
-                } // Main Row
-                //-- Separator
-                Rectangle {
-                    width:          parent.width
-                    height:         1
-                    border.color:   qgcPal.text
-                    border.width:   1
+                TabButton {
+                    text:       qsTr("Calibration")
                 }
-                //-- Button Actions
-                QGCLabel { text: qsTr("Button actions:"); visible: !activeVehicle.supportsJSButton; }
-                Flow {
-                    width:      parent.width
-                    spacing:    ScreenTools.defaultFontPixelWidth
-                    visible:    !activeVehicle.supportsJSButton
-                    Repeater {
-                        id:     buttonActionRepeater
-                        model:  _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : []
-                        Row {
-                            spacing: ScreenTools.defaultFontPixelWidth
-                            visible: !activeVehicle.supportsJSButton
-                            property bool pressed
-                            QGCCheckBox {
-                                anchors.verticalCenter:     parent.verticalCenter
-                                checked:                    _activeJoystick ? _activeJoystick.buttonActions[modelData] !== "" : false
-                                onClicked: _activeJoystick.setButtonAction(modelData, checked ? buttonActionCombo.textAt(buttonActionCombo.currentIndex) : "")
-                            }
-                            Rectangle {
-                                anchors.verticalCenter:     parent.verticalCenter
-                                width:                      ScreenTools.defaultFontPixelHeight * 1.5
-                                height:                     width
-                                border.width:               1
-                                border.color:               qgcPal.text
-                                color:                      pressed ? qgcPal.buttonHighlight : qgcPal.button
-                                QGCLabel {
-                                    anchors.fill:           parent
-                                    color:                  pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
-                                    horizontalAlignment:    Text.AlignHCenter
-                                    verticalAlignment:      Text.AlignVCenter
-                                    text:                   modelData
-                                }
-                            }
-                            QGCComboBox {
-                                id:                         buttonActionCombo
-                                width:                      ScreenTools.defaultFontPixelWidth * 20
-                                model:                      _activeJoystick ? _activeJoystick.actions : 0
-
-                                onActivated:                _activeJoystick.setButtonAction(modelData, textAt(index))
-                                Component.onCompleted:      currentIndex = find(_activeJoystick.buttonActions[modelData])
-                            }
-                        }
-                    }
+                TabButton {
+                    text:       qsTr("Advanced")
                 }
             }
-            // Live axis monitor control component
-            Component {
-                id: axisMonitorDisplayComponent
-
-                Item {
-                    property int    axisValue:          0
-                    property int    deadbandValue:      0
-                    property bool   narrowIndicator:    false
-                    property color  deadbandColor:      "#8c161a"
 
-                    property color  __barColor:         qgcPal.windowShade
+            property var pages:  ["JoystickConfigGeneral.qml", "JoystickConfigButtons.qml", "JoystickConfigCalibration.qml", "JoystickConfigAdvanced.qml"]
 
-                    // Bar
-                    Rectangle {
-                        id:                     bar
-                        anchors.verticalCenter: parent.verticalCenter
-                        width:                  parent.width
-                        height:                 parent.height / 2
-                        color:                  __barColor
-                    }
-
-                    // Deadband
-                    Rectangle {
-                        id:                     deadbandBar
-                        anchors.verticalCenter: parent.verticalCenter
-                        x:                      _deadbandPosition
-                        width:                  _deadbandWidth
-                        height:                 parent.height / 2
-                        color:                  deadbandColor
-                        visible:                controller.deadbandToggle
-
-                        property real _percentDeadband:     ((2 * deadbandValue) / (32768.0 * 2))
-                        property real _deadbandWidth:       parent.width * _percentDeadband
-                        property real _deadbandPosition:    (parent.width - _deadbandWidth) / 2
-                    }
-
-                    // Center point
-                    Rectangle {
-                        anchors.horizontalCenter:   parent.horizontalCenter
-                        width:                      ScreenTools.defaultFontPixelWidth / 2
-                        height:                     parent.height
-                        color:                      qgcPal.window
-                    }
-
-                    // Indicator
-                    Rectangle {
-                        anchors.verticalCenter: parent.verticalCenter
-                        width:                  parent.narrowIndicator ?  height/6 : height
-                        height:                 parent.height * 0.75
-                        x:                      (reversed ? (parent.width - _indicatorPosition) : _indicatorPosition) - (width / 2)
-                        radius:                 width / 2
-                        color:                  qgcPal.text
-                        visible:                mapped
-
-                        property real _percentAxisValue:    ((axisValue + 32768.0) / (32768.0 * 2))
-                        property real _indicatorPosition:   parent.width * _percentAxisValue
-                    }
-
-                    QGCLabel {
-                        anchors.fill:           parent
-                        horizontalAlignment:    Text.AlignHCenter
-                        verticalAlignment:      Text.AlignVCenter
-                        text:                   qsTr("Not Mapped")
-                        visible:                !mapped
-                    }
-
-                    ColorAnimation {
-                        id:         barAnimation
-                        target:     bar
-                        property:   "color"
-                        from:       "yellow"
-                        to:         __barColor
-                        duration:   1500
-                    }
-
-
-                    // Axis value debugger
-                    /*
-                    QGCLabel {
-                        anchors.fill: parent
-                        text: axisValue
-                    }
-                    */
-
-                }
-            } // Component - axisMonitorDisplayComponent
-        } // Item
-    } // Component - pageComponent
-} // SetupPage
+            Loader {
+                id:             joyLoader
+                source:         pages[bar.currentIndex]
+                width:          parent.width
+                anchors.top:    bar.bottom
+            }
+        }
+    }
+}
 
 
diff --git a/src/VehicleSetup/JoystickConfigAdvanced.qml b/src/VehicleSetup/JoystickConfigAdvanced.qml
new file mode 100644
index 0000000..1e4a4e8
--- /dev/null
+++ b/src/VehicleSetup/JoystickConfigAdvanced.qml
@@ -0,0 +1,186 @@
+/****************************************************************************
+ *
+ *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick                      2.11
+import QtQuick.Controls             2.4
+import QtQuick.Dialogs              1.3
+import QtQuick.Layouts              1.11
+
+import QGroundControl               1.0
+import QGroundControl.Palette       1.0
+import QGroundControl.Controls      1.0
+import QGroundControl.ScreenTools   1.0
+import QGroundControl.Controllers   1.0
+import QGroundControl.FactSystem    1.0
+import QGroundControl.FactControls  1.0
+
+Item {
+    width:                  grid.width  + (ScreenTools.defaultFontPixelWidth  * 2)
+    height:                 grid.height + (ScreenTools.defaultFontPixelHeight * 2)
+    //---------------------------------------------------------------------
+    GridLayout {
+        id:                 grid
+        columns:            2
+        columnSpacing:      ScreenTools.defaultFontPixelWidth
+        rowSpacing:         ScreenTools.defaultFontPixelHeight
+        anchors.centerIn:   parent
+        //-------------------------------------------------------------
+        //-------------------------------------------------------------
+        QGCRadioButton {
+            text:               qsTr("Full down stick is zero throttle")
+            checked:            _activeJoystick ? _activeJoystick.throttleMode === 1 : false
+            onClicked:          _activeJoystick.throttleMode = 1
+            Layout.columnSpan:  2
+        }
+        QGCRadioButton {
+            text:               qsTr("Center stick is zero throttle")
+            checked:            _activeJoystick ? _activeJoystick.throttleMode === 0 : false
+            onClicked:          _activeJoystick.throttleMode = 0
+            Layout.columnSpan:  2
+        }
+        //-------------------------------------------------------------
+        QGCLabel {
+            text:               qsTr("Spring loaded throttle smoothing")
+            visible:            _activeJoystick ? _activeJoystick.throttleMode === 0 : false
+            Layout.alignment:   Qt.AlignVCenter
+            Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 36
+        }
+        QGCCheckBox {
+            checked:            _activeJoystick ? _activeJoystick.accumulator : false
+            visible:            _activeJoystick ? _activeJoystick.throttleMode === 0 : false
+            onClicked:          _activeJoystick.accumulator = checked
+        }
+        //-------------------------------------------------------------
+        QGCLabel {
+            text:               qsTr("Allow negative Thrust")
+            visible:            activeVehicle.supportsNegativeThrust
+            Layout.alignment:   Qt.AlignVCenter
+        }
+        QGCCheckBox {
+            visible:            activeVehicle.supportsNegativeThrust
+            enabled:            _activeJoystick.negativeThrust = activeVehicle.supportsNegativeThrust
+            checked:            _activeJoystick ? _activeJoystick.negativeThrust : false
+            onClicked:          _activeJoystick.negativeThrust = checked
+        }
+        //---------------------------------------------------------------------
+        QGCLabel {
+            text:               qsTr("Exponential:")
+        }
+        Row {
+            spacing:            ScreenTools.defaultFontPixelWidth
+            QGCSlider {
+                id:             expoSlider
+                width:          ScreenTools.defaultFontPixelWidth * 20
+                minimumValue:   0
+                maximumValue:   0.75
+                Component.onCompleted: value = -_activeJoystick.exponential
+                onValueChanged: _activeJoystick.exponential = -value
+             }
+            QGCLabel {
+                id:     expoSliderIndicator
+                text:   expoSlider.value.toFixed(2)
+            }
+        }
+        //-----------------------------------------------------------------
+        //-- Enable Advanced Mode
+        QGCLabel {
+            text:               qsTr("Enable further advanced settings (careful!)")
+            Layout.alignment:   Qt.AlignVCenter
+            Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 36
+        }
+        QGCCheckBox {
+            id:         advancedSettings
+            checked:    activeVehicle.joystickMode !== 0
+            onClicked: {
+                if (!checked) {
+                    activeVehicle.joystickMode = 0
+                }
+            }
+        }
+        //-----------------------------------------------------------------
+        //-- Mode
+        QGCLabel {
+            Layout.alignment:   Qt.AlignVCenter
+            text:               qsTr("Joystick mode:")
+            visible:            advancedSettings.checked
+        }
+        QGCComboBox {
+            enabled:            advancedSettings.checked
+            currentIndex:       activeVehicle.joystickMode
+            width:              ScreenTools.defaultFontPixelWidth * 20
+            model:              activeVehicle.joystickModes
+            onActivated:        activeVehicle.joystickMode = index
+            Layout.alignment:   Qt.AlignVCenter
+            visible:            advancedSettings.checked
+        }
+        //-----------------------------------------------------------------
+        //-- Message Frequency
+        QGCLabel {
+            text:               qsTr("Message frequency (Hz):")
+            Layout.alignment:   Qt.AlignVCenter
+            visible:            advancedSettings.checked
+        }
+        QGCTextField {
+            text:               _activeJoystick.frequency
+            enabled:            advancedSettings.checked
+            validator:          DoubleValidator { bottom: 0.25; top: 100.0; }
+            inputMethodHints:   Qt.ImhFormattedNumbersOnly
+            Layout.alignment:   Qt.AlignVCenter
+            onEditingFinished: {
+                _activeJoystick.frequency = parseFloat(text)
+            }
+            visible:            advancedSettings.checked
+        }
+        //-----------------------------------------------------------------
+        //-- Enable circle correction
+        QGCLabel {
+            text:               qsTr("Enable circle correction")
+            Layout.alignment:   Qt.AlignVCenter
+            visible:            advancedSettings.checked
+        }
+        QGCCheckBox {
+            checked:            activeVehicle.joystickMode !== 0
+            enabled:            advancedSettings.checked
+            Component.onCompleted: {
+                checked = _activeJoystick.circleCorrection
+            }
+            onClicked: {
+                _activeJoystick.circleCorrection = checked
+            }
+            visible:            advancedSettings.checked
+        }
+        //-----------------------------------------------------------------
+        //-- Deadband
+        QGCLabel {
+            text:               qsTr("Deadbands")
+            Layout.alignment:   Qt.AlignVCenter
+            visible:            advancedSettings.checked
+        }
+        QGCCheckBox {
+            enabled:            advancedSettings.checked
+            checked:            controller.deadbandToggle
+            onClicked:          controller.deadbandToggle = checked
+            Layout.alignment:   Qt.AlignVCenter
+            visible:            advancedSettings.checked
+        }
+        QGCLabel{
+            Layout.fillWidth:   true
+            Layout.columnSpan:  2
+            font.pointSize:     ScreenTools.smallFontPointSize
+            wrapMode:           Text.WordWrap
+            visible:            advancedSettings.checked
+            text:   qsTr("Deadband can be set during the first ") +
+                    qsTr("step of calibration by gently wiggling each axis. ") +
+                    qsTr("Deadband can also be adjusted by clicking and ") +
+                    qsTr("dragging vertically on the corresponding axis monitor.")
+        }
+    }
+}
+
+
diff --git a/src/VehicleSetup/JoystickConfigButtons.qml b/src/VehicleSetup/JoystickConfigButtons.qml
new file mode 100644
index 0000000..6c32587
--- /dev/null
+++ b/src/VehicleSetup/JoystickConfigButtons.qml
@@ -0,0 +1,146 @@
+/****************************************************************************
+ *
+ *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick                      2.11
+import QtQuick.Controls             2.4
+import QtQuick.Dialogs              1.3
+import QtQuick.Layouts              1.11
+
+import QGroundControl               1.0
+import QGroundControl.Palette       1.0
+import QGroundControl.Controls      1.0
+import QGroundControl.ScreenTools   1.0
+import QGroundControl.Controllers   1.0
+import QGroundControl.FactSystem    1.0
+import QGroundControl.FactControls  1.0
+
+Item {
+    width:                  availableWidth
+    height:                 (activeVehicle.supportsJSButton ? buttonCol.height : buttonFlow.height) + (ScreenTools.defaultFontPixelHeight * 2)
+    Connections {
+        target: _activeJoystick
+        onRawButtonPressedChanged: {
+            if (buttonActionRepeater.itemAt(index)) {
+                buttonActionRepeater.itemAt(index).pressed = pressed
+            }
+            if (jsButtonActionRepeater.itemAt(index)) {
+                jsButtonActionRepeater.itemAt(index).pressed = pressed
+            }
+        }
+    }
+    Flow {
+        id:                 buttonFlow
+        width:              parent.width
+        spacing:            ScreenTools.defaultFontPixelWidth
+        visible:            !activeVehicle.supportsJSButton
+        anchors.centerIn:   parent
+        Repeater {
+            id:             buttonActionRepeater
+            model:          _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : []
+            Row {
+                spacing:    ScreenTools.defaultFontPixelWidth
+                property bool pressed
+                QGCCheckBox {
+                    anchors.verticalCenter:     parent.verticalCenter
+                    checked:                    _activeJoystick ? _activeJoystick.buttonActions[modelData] !== "" : false
+                    onClicked:                  _activeJoystick.setButtonAction(modelData, checked ? buttonActionCombo.textAt(buttonActionCombo.currentIndex) : "")
+                }
+                Rectangle {
+                    anchors.verticalCenter:     parent.verticalCenter
+                    width:                      ScreenTools.defaultFontPixelHeight * 1.5
+                    height:                     width
+                    border.width:               1
+                    border.color:               qgcPal.text
+                    color:                      pressed ? qgcPal.buttonHighlight : qgcPal.button
+                    QGCLabel {
+                        anchors.fill:           parent
+                        color:                  pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
+                        horizontalAlignment:    Text.AlignHCenter
+                        verticalAlignment:      Text.AlignVCenter
+                        text:                   modelData
+                    }
+                }
+                QGCComboBox {
+                    id:                         buttonActionCombo
+                    width:                      ScreenTools.defaultFontPixelWidth * 20
+                    model:                      _activeJoystick ? _activeJoystick.actions : 0
+                    onActivated:                _activeJoystick.setButtonAction(modelData, textAt(index))
+                    Component.onCompleted:      currentIndex = find(_activeJoystick.buttonActions[modelData])
+                }
+            }
+        }
+    }
+    Column {
+        id:         buttonCol
+        width:      parent.width
+        visible:    activeVehicle.supportsJSButton
+        spacing:    ScreenTools.defaultFontPixelHeight / 3
+        Row {
+            spacing: ScreenTools.defaultFontPixelWidth
+            QGCLabel {
+                horizontalAlignment:    Text.AlignHCenter
+                width:                  ScreenTools.defaultFontPixelHeight * 1.5
+                text:                   qsTr("#")
+            }
+            QGCLabel {
+                width:                  ScreenTools.defaultFontPixelWidth * 15
+                text:                   qsTr("Function: ")
+            }
+            QGCLabel {
+                width:                  ScreenTools.defaultFontPixelWidth * 15
+                text:                   qsTr("Shift Function: ")
+            }
+        }
+        Repeater {
+            id:     jsButtonActionRepeater
+            model:  _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : 0
+
+            Row {
+                spacing: ScreenTools.defaultFontPixelWidth
+                visible: activeVehicle.supportsJSButton
+
+                property bool pressed
+
+                Rectangle {
+                    anchors.verticalCenter:     parent.verticalCenter
+                    width:                      ScreenTools.defaultFontPixelHeight * 1.5
+                    height:                     width
+                    border.width:               1
+                    border.color:               qgcPal.text
+                    color:                      pressed ? qgcPal.buttonHighlight : qgcPal.button
+
+
+                    QGCLabel {
+                        anchors.fill:           parent
+                        color:                  pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
+                        horizontalAlignment:    Text.AlignHCenter
+                        verticalAlignment:      Text.AlignVCenter
+                        text:                   modelData
+                    }
+                }
+
+                FactComboBox {
+                    id:         mainJSButtonActionCombo
+                    width:      ScreenTools.defaultFontPixelWidth * 15
+                    fact:       controller.parameterExists(-1, "BTN"+index+"_FUNCTION") ? controller.getParameterFact(-1, "BTN" + index + "_FUNCTION") : null;
+                    indexModel: false
+                }
+
+                FactComboBox {
+                    id:         shiftJSButtonActionCombo
+                    width:      ScreenTools.defaultFontPixelWidth * 15
+                    fact:       controller.parameterExists(-1, "BTN"+index+"_SFUNCTION") ? controller.getParameterFact(-1, "BTN" + index + "_SFUNCTION") : null;
+                    indexModel: false
+                }
+            }
+        }
+    }
+}
+
+
diff --git a/src/VehicleSetup/JoystickConfigCalibration.qml b/src/VehicleSetup/JoystickConfigCalibration.qml
new file mode 100644
index 0000000..c4f01c0
--- /dev/null
+++ b/src/VehicleSetup/JoystickConfigCalibration.qml
@@ -0,0 +1,241 @@
+/****************************************************************************
+ *
+ *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick                      2.11
+import QtQuick.Controls             2.4
+import QtQuick.Dialogs              1.3
+import QtQuick.Layouts              1.11
+
+import QGroundControl               1.0
+import QGroundControl.Palette       1.0
+import QGroundControl.Controls      1.0
+import QGroundControl.ScreenTools   1.0
+import QGroundControl.Controllers   1.0
+import QGroundControl.FactSystem    1.0
+import QGroundControl.FactControls  1.0
+
+Item {
+    height:                 calCol.height + ScreenTools.defaultFontPixelHeight * 2
+    width:                  calCol.width  + ScreenTools.defaultFontPixelWidth  * 2
+    Column {
+        id:                 calCol
+        spacing:            ScreenTools.defaultFontPixelHeight
+        anchors.centerIn:   parent
+        Row {
+            spacing:            ScreenTools.defaultFontPixelWidth * 4
+            anchors.horizontalCenter: parent.horizontalCenter
+            //-----------------------------------------------------------------
+            // Calibration
+            Column {
+                spacing:            ScreenTools.defaultFontPixelHeight
+                anchors.verticalCenter: parent.verticalCenter
+                Rectangle {
+                    width:          Math.round(ScreenTools.defaultFontPixelWidth * 45)
+                    height:         Math.round(width * 0.5)
+                    radius:         ScreenTools.defaultFontPixelWidth * 2
+                    color:          qgcPal.window
+                    border.color:   qgcPal.text
+                    border.width:   ScreenTools.defaultFontPixelWidth * 0.25
+                    anchors.horizontalCenter: parent.horizontalCenter
+                    property bool hasStickPositions: controller.stickPositions.length === 4
+                    //---------------------------------------------------------
+                    //-- Left Stick
+                    Rectangle {
+                        width:      parent.width * 0.25
+                        height:     width
+                        radius:     width * 0.5
+                        color:      qgcPal.window
+                        border.color: qgcPal.text
+                        border.width: ScreenTools.defaultFontPixelWidth * 0.125
+                        x:          (parent.width  * 0.25) - (width  * 0.5)
+                        y:          (parent.height * 0.5)  - (height * 0.5)
+                    }
+                    Rectangle {
+                        color:  qgcPal.colorGreen
+                        width:  parent.width * 0.035
+                        height: width
+                        radius: width * 0.5
+                        visible: parent.hasStickPositions
+                        x:      (parent.width  * controller.stickPositions[0]) - (width  * 0.5)
+                        y:      (parent.height * controller.stickPositions[1]) - (height * 0.5)
+                    }
+                    //---------------------------------------------------------
+                    //-- Right Stick
+                    Rectangle {
+                        width:      parent.width * 0.25
+                        height:     width
+                        radius:     width * 0.5
+                        color:      qgcPal.window
+                        border.color: qgcPal.text
+                        border.width: ScreenTools.defaultFontPixelWidth * 0.125
+                        x:          (parent.width  * 0.75) - (width  * 0.5)
+                        y:          (parent.height * 0.5)  - (height * 0.5)
+                    }
+                    Rectangle {
+                        color:  qgcPal.colorGreen
+                        width:  parent.width * 0.035
+                        height: width
+                        radius: width * 0.5
+                        visible: parent.hasStickPositions
+                        x:      (parent.width  * controller.stickPositions[2]) - (width  * 0.5)
+                        y:      (parent.height * controller.stickPositions[3]) - (height * 0.5)
+                    }
+                    //---------------------------------------------------------
+                    //-- Gimbal Pitch
+                    Rectangle {
+                        width:      ScreenTools.defaultFontPixelWidth * 0.125
+                        height:     parent.height * 0.2
+                        color:      qgcPal.text
+                        visible:    controller.hasGimbal
+                        x:          (parent.width  * 0.5) - (width  * 0.5)
+                        y:          (parent.height * 0.5) - (height * 0.5)
+                    }
+                    Rectangle {
+                        color:      qgcPal.colorGreen
+                        width:      parent.width * 0.035
+                        height:     width
+                        radius:     width * 0.5
+                        visible:    controller.hasGimbal
+                        x:          (parent.width  * controller.gimbalPositions[0]) - (width  * 0.5)
+                        y:          (parent.height * controller.gimbalPositions[1]) - (height * 0.5)
+                    }
+                    //---------------------------------------------------------
+                    //-- Gimbal Yaw
+                    Rectangle {
+                        width:      parent.width * 0.2
+                        height:     ScreenTools.defaultFontPixelWidth * 0.125
+                        color:      qgcPal.text
+                        visible:    controller.hasGimbal
+                        x:          (parent.width  * 0.5) - (width  * 0.5)
+                        y:          (parent.height * 0.3) - (height * 0.5)
+                    }
+                    Rectangle {
+                        color:      qgcPal.colorGreen
+                        width:      parent.width * 0.035
+                        height:     width
+                        radius:     width * 0.5
+                        visible:    controller.hasGimbal
+                        x:          (parent.width  * controller.gimbalPositions[2]) - (width  * 0.5)
+                        y:          (parent.height * controller.gimbalPositions[3]) - (height * 0.5)
+                    }
+                }
+            }
+            //---------------------------------------------------------------------
+            // Monitor
+            Column {
+                spacing:            ScreenTools.defaultFontPixelHeight * 0.5
+                anchors.verticalCenter: parent.verticalCenter
+                QGCLabel {
+                    text:           qsTr("Axis Monitor")
+                    anchors.horizontalCenter: parent.horizontalCenter
+                }
+                Connections {
+                    target: controller
+                    onAxisValueChanged: {
+                        if (axisMonitorRepeater.itemAt(axis)) {
+                            axisMonitorRepeater.itemAt(axis).axis.axisValue = value
+                        }
+                    }
+                    onAxisDeadbandChanged: {
+                        if (axisMonitorRepeater.itemAt(axis)) {
+                            axisMonitorRepeater.itemAt(axis).axis.deadbandValue = value
+                        }
+                    }
+                }
+                Repeater {
+                    id:             axisMonitorRepeater
+                    model:          _activeJoystick ? _activeJoystick.axisCount : 0
+                    width:          parent.width
+                    Row {
+                        spacing:    5
+                        anchors.horizontalCenter: parent.horizontalCenter
+                        // Need this to get to loader from Connections above
+                        property Item axis: theAxis
+                        QGCLabel {
+                            id:     axisLabel
+                            text:   modelData
+                        }
+                        AxisMonitor {
+                            id:                     theAxis
+                            anchors.verticalCenter: axisLabel.verticalCenter
+                            height:                 ScreenTools.defaultFontPixelHeight
+                            width:                  200
+                            narrowIndicator:        true
+                            mapped:                 true
+                            reversed:               false
+                            MouseArea {
+                                id:                 deadbandMouseArea
+                                anchors.fill:       parent.item
+                                enabled:            controller.deadbandToggle
+                                preventStealing:    true
+                                property real startX
+                                property real direction
+                                onPressed: {
+                                    startX = mouseX
+                                    direction = startX > width/2 ? 1 : -1
+                                    parent.item.deadbandColor = "#3C6315"
+                                }
+                                onPositionChanged: {
+                                    var mouseToDeadband = 32768/(width/2) // Factor to have deadband follow the mouse movement
+                                    var newValue = parent.item.deadbandValue + direction*(mouseX - startX)*mouseToDeadband
+                                    if ((newValue > 0) && (newValue <32768)){parent.item.deadbandValue=newValue;}
+                                    startX = mouseX
+                                }
+                                onReleased: {
+                                    controller.setDeadbandValue(modelData,parent.item.deadbandValue)
+                                    parent.item.deadbandColor = "#8c161a"
+                                }
+                            }
+                        }
+                    }
+                }
+            }
+        }
+        // Command Buttons
+        Row {
+            spacing:            ScreenTools.defaultFontPixelWidth * 2
+            visible:            _activeJoystick.requiresCalibration
+            anchors.horizontalCenter: parent.horizontalCenter
+            QGCButton {
+                id:         skipButton
+                text:       qsTr("Skip")
+                enabled:    controller.calibrating ? controller.skipEnabled : false
+                width:      ScreenTools.defaultFontPixelWidth * 10
+                onClicked:  controller.skipButtonClicked()
+            }
+            QGCButton {
+                text:       qsTr("Cancel")
+                width:      ScreenTools.defaultFontPixelWidth * 10
+                enabled:    controller.calibrating
+                onClicked: {
+                    if(controller.calibrating)
+                        controller.cancelButtonClicked()
+                }
+            }
+            QGCButton {
+                id:         nextButton
+                primary:    true
+                enabled:    controller.calibrating ? controller.nextEnabled : true
+                text:       controller.calibrating ? qsTr("Next") : qsTr("Start")
+                width:      ScreenTools.defaultFontPixelWidth * 10
+                onClicked:  controller.nextButtonClicked()
+            }
+        }
+        // Status Text
+        QGCLabel {
+            text:           controller.statusText
+            width:          parent.width * 0.8
+            wrapMode:       Text.WordWrap
+            horizontalAlignment: Text.AlignHCenter
+            anchors.horizontalCenter: parent.horizontalCenter
+        }
+    }
+}
+
+
diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc
index c97a9ca..6025a86 100644
--- a/src/VehicleSetup/JoystickConfigController.cc
+++ b/src/VehicleSetup/JoystickConfigController.cc
@@ -28,21 +28,6 @@ const int JoystickConfigController::_calMinDelta =          1000;       ///< Amo
 
 const int JoystickConfigController::_stickDetectSettleMSecs = 500;
 
-const char*  JoystickConfigController::_imageFilePrefix =   "calibration/joystick/";
-const char*  JoystickConfigController::_imageFileMode1Dir = "mode1/";
-const char*  JoystickConfigController::_imageFileMode2Dir = "mode2/";
-const char*  JoystickConfigController::_imageFileMode3Dir = "mode3/";
-const char*  JoystickConfigController::_imageFileMode4Dir = "mode4/";
-const char*  JoystickConfigController::_imageCenter =       "joystickCenter.png";
-const char*  JoystickConfigController::_imageThrottleUp =   "joystickThrottleUp.png";
-const char*  JoystickConfigController::_imageThrottleDown = "joystickThrottleDown.png";
-const char*  JoystickConfigController::_imageYawLeft =      "joystickYawLeft.png";
-const char*  JoystickConfigController::_imageYawRight =     "joystickYawRight.png";
-const char*  JoystickConfigController::_imageRollLeft =     "joystickRollLeft.png";
-const char*  JoystickConfigController::_imageRollRight =    "joystickRollRight.png";
-const char*  JoystickConfigController::_imagePitchUp =      "joystickPitchUp.png";
-const char*  JoystickConfigController::_imagePitchDown =    "joystickPitchDown.png";
-
 static const JoystickConfigController::stateStickPositions stSticksCentered {
     0.25, 0.5, 0.75, 0.5
 };
@@ -137,7 +122,7 @@ JoystickConfigController::~JoystickConfigController()
 /// @brief Returns the state machine entry for the specified state.
 const JoystickConfigController::stateMachineEntry* JoystickConfigController::_getStateMachineEntry(int step)
 {
-    static const char* msgBegin =               "Allow all sticks to center as shown in diagram.\n\nClick Next to continue";
+    static const char* msgBegin =               "Allow all sticks to center as shown in diagram.\nClick Next to continue";
     static const char* msgThrottleUp =          "Move the Throttle stick all the way up and hold it there...";
     static const char* msgThrottleDown =        "Move the Throttle stick all the way down and hold it there...";
     static const char* msgYawLeft =             "Move the Yaw stick all the way to the left and hold it there...";
@@ -151,7 +136,7 @@ const JoystickConfigController::stateMachineEntry* JoystickConfigController::_ge
     static const char* msgGimbalPitchUp =       "Move the Gimbal Pitch control all the way up and hold it there...";
     static const char* msgGimbalYawLeft =       "Move the Gimbal Yaw control all the way to the left and hold it there...";
     static const char* msgGimbalYawRight =      "Move the Gimbal Yaw control all the way to the right and hold it there...";
-    static const char* msgComplete =            "All settings have been captured. Click Next to enable the joystick.";
+    static const char* msgComplete =            "All settings have been captured.\nClick Next to enable the joystick.";
 
     static const stateMachineEntry rgStateMachine[] = {
         //Function
@@ -189,6 +174,24 @@ void JoystickConfigController::_advanceState()
     _setupCurrentState();
 }
 
+bool JoystickConfigController::nextEnabled()
+{
+    if(_currentStep >= 0) {
+        const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
+        return state->nextFn != nullptr;
+    }
+    return false;
+}
+
+bool JoystickConfigController::skipEnabled()
+{
+    if(_currentStep >= 0) {
+        const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
+        return state->skipFn != nullptr;
+    }
+    return false;
+}
+
 /// @brief Sets up the state machine according to the current step from _currentStep.
 void JoystickConfigController::_setupCurrentState()
 {
@@ -197,14 +200,14 @@ void JoystickConfigController::_setupCurrentState()
     _stickDetectAxis = _axisNoAxis;
     _stickDetectSettleStarted = false;
     _calSaveCurrentValues();
-    _nextButton->setEnabled(state->nextFn != nullptr);
-    _skipButton->setEnabled(state->skipFn != nullptr);
     _currentStickPositions.clear();
     _currentStickPositions << state->stickPositions.leftX << state->stickPositions.leftY << state->stickPositions.rightX << state->stickPositions.rightY;
     _currentGimbalPositions.clear();
     _currentGimbalPositions << state->gimbalPositions.leftX << state->gimbalPositions.leftY << state->gimbalPositions.rightX << state->gimbalPositions.rightY;
     emit stickPositionsChanged();
     emit gimbalPositionsChanged();
+    emit nextEnabledChanged();
+    emit skipEnabledChanged();
 }
 
 void JoystickConfigController::_axisValueChanged(int axis, int value)
@@ -300,7 +303,6 @@ void JoystickConfigController::_inputCenterWaitBegin(Joystick::AxisFunction_t fu
     if ((abs(value) * 1.1f > _rgAxisInfo[axis].deadband) && (_activeJoystick->deadband())) {   //add 10% on top of existing deadband
         _axisDeadbandChanged(axis, static_cast<int>(abs(value) * 1.1f));
     }
-    _nextButton->setEnabled(true);
     // FIXME: Doesn't wait for center
 }
 
@@ -588,8 +590,6 @@ void JoystickConfigController::_startCalibration()
 {
     _activeJoystick->setCalibrationMode(true);
     _resetInternalCalibrationValues();
-    _nextButton->setProperty("text", "Next");
-    _cancelButton->setEnabled(true);
     _currentStep = 0;
     _setupCurrentState();
     emit calibratingChanged();
@@ -602,11 +602,13 @@ void JoystickConfigController::_stopCalibration()
     _activeJoystick->setCalibrationMode(false);
     _setInternalCalibrationValuesFromSettings();
     _setStatusText("");
-    _nextButton->setProperty("text", tr("Calibrate"));
-    _nextButton->setEnabled(true);
-    _cancelButton->setEnabled(false);
-    _skipButton->setEnabled(false);
     emit calibratingChanged();
+    _currentStickPositions.clear();
+    _currentGimbalPositions.clear();
+    _currentStickPositions  << _sticksCentered.leftX  << _sticksCentered.leftY  << _sticksCentered.rightX  << _sticksCentered.rightY;
+    _currentGimbalPositions << stGimbalCentered.leftX << stGimbalCentered.leftY << stGimbalCentered.rightX << stGimbalCentered.rightY;
+    emit stickPositionsChanged();
+    emit gimbalPositionsChanged();
 }
 
 /// @brief Saves the current axis values, so that we can detect when the use moves an input.
@@ -618,22 +620,6 @@ void JoystickConfigController::_calSaveCurrentValues()
     }
 }
 
-/// @brief Set up the Save state of calibration.
-void JoystickConfigController::_calSave()
-{
-    _calState = calStateSave;
-    _setStatusText(tr(
-        "The current calibration settings are now displayed for each axis on screen.\n\n"
-        "Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."));
-    _nextButton->setEnabled(true);
-    _skipButton->setEnabled(false);
-    _cancelButton->setEnabled(true);
-    
-    // This updates the internal values according to the validation rules. Then _updateView will tick and update ui
-    // such that the settings that will be written out are displayed.
-    _validateCalibration();
-}
-
 void JoystickConfigController::_setStickPositions()
 {
     _sticksCentered = stSticksCentered;
diff --git a/src/VehicleSetup/JoystickConfigController.h b/src/VehicleSetup/JoystickConfigController.h
index ec2086f..f79e0d5 100644
--- a/src/VehicleSetup/JoystickConfigController.h
+++ b/src/VehicleSetup/JoystickConfigController.h
@@ -41,10 +41,6 @@ public:
     
     Q_PROPERTY(QString statusText               READ statusText                 NOTIFY statusTextChanged)
 
-    Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
-    Q_PROPERTY(QQuickItem* nextButton   MEMBER _nextButton)
-    Q_PROPERTY(QQuickItem* skipButton   MEMBER _skipButton)
-    
     Q_PROPERTY(bool rollAxisMapped              READ rollAxisMapped             NOTIFY rollAxisMappedChanged)
     Q_PROPERTY(bool pitchAxisMapped             READ pitchAxisMapped            NOTIFY pitchAxisMappedChanged)
     Q_PROPERTY(bool yawAxisMapped               READ yawAxisMapped              NOTIFY yawAxisMappedChanged)
@@ -66,6 +62,8 @@ public:
 
     Q_PROPERTY(int  transmitterMode             READ transmitterMode            WRITE setTransmitterMode NOTIFY transmitterModeChanged)
     Q_PROPERTY(bool calibrating                 READ calibrating                NOTIFY calibratingChanged)
+    Q_PROPERTY(bool nextEnabled                 READ nextEnabled                NOTIFY nextEnabledChanged)
+    Q_PROPERTY(bool skipEnabled                 READ skipEnabled                NOTIFY skipEnabledChanged)
 
     Q_PROPERTY(QList<qreal> stickPositions      READ stickPositions             NOTIFY stickPositionsChanged)
     Q_PROPERTY(QList<qreal> gimbalPositions     READ gimbalPositions            NOTIFY gimbalPositionsChanged)
@@ -103,6 +101,8 @@ public:
     void setTransmitterMode                 (int mode);
 
     bool calibrating                        () { return _currentStep != -1; }
+    bool nextEnabled                        ();
+    bool skipEnabled                        ();
 
     QList<qreal> stickPositions             () { return _currentStickPositions; }
     QList<qreal> gimbalPositions            () { return _currentGimbalPositions; }
@@ -132,6 +132,8 @@ signals:
     void deadbandToggled                    (bool value);
     void transmitterModeChanged             (int mode);
     void calibratingChanged                 ();
+    void nextEnabledChanged                 ();
+    void skipEnabledChanged                 ();
     void stickPositionsChanged              ();
     void gimbalPositionsChanged             ();
     void hasGimbalChanged                   ();
@@ -213,7 +215,6 @@ private:
     
     void _startCalibration      ();
     void _stopCalibration       ();
-    void _calSave               ();
 
     void _calSaveCurrentValues  ();
     
@@ -223,23 +224,6 @@ private:
 
     void _setStatusText         (const QString& text);
     
-    // Member variables
-
-    static const char* _imageFileMode1Dir;
-    static const char* _imageFileMode2Dir;
-    static const char* _imageFileMode3Dir;
-    static const char* _imageFileMode4Dir;
-    static const char* _imageFilePrefix;
-    static const char* _imageCenter;
-    static const char* _imageThrottleUp;
-    static const char* _imageThrottleDown;
-    static const char* _imageYawLeft;
-    static const char* _imageYawRight;
-    static const char* _imageRollLeft;
-    static const char* _imageRollRight;
-    static const char* _imagePitchUp;
-    static const char* _imagePitchDown;
-
     stateStickPositions _sticksCentered;
     stateStickPositions _sticksThrottleUp;
     stateStickPositions _sticksThrottleDown;
@@ -286,14 +270,10 @@ private:
     int     _stickDetectValue;
     bool    _stickDetectSettleStarted;
     QTime   _stickDetectSettleElapsed;
-    static const int _stickDetectSettleMSecs;
 
-    QString     _statusText;
+    static const int _stickDetectSettleMSecs;
 
-    QQuickItem* _cancelButton   = nullptr;
-    QQuickItem* _nextButton     = nullptr;
-    QQuickItem* _skipButton     = nullptr;
-    
+    QString             _statusText;
     JoystickManager*    _joystickManager;
 };
 
diff --git a/src/VehicleSetup/JoystickConfigGeneral.qml b/src/VehicleSetup/JoystickConfigGeneral.qml
new file mode 100644
index 0000000..dbca886
--- /dev/null
+++ b/src/VehicleSetup/JoystickConfigGeneral.qml
@@ -0,0 +1,298 @@
+/****************************************************************************
+ *
+ *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick                      2.11
+import QtQuick.Controls             2.4
+import QtQuick.Dialogs              1.3
+import QtQuick.Layouts              1.11
+
+import QGroundControl               1.0
+import QGroundControl.Palette       1.0
+import QGroundControl.Controls      1.0
+import QGroundControl.ScreenTools   1.0
+import QGroundControl.Controllers   1.0
+import QGroundControl.FactSystem    1.0
+import QGroundControl.FactControls  1.0
+
+Item {
+    width:                  mainCol.width  + (ScreenTools.defaultFontPixelWidth  * 2)
+    height:                 mainCol.height + (ScreenTools.defaultFontPixelHeight * 2)
+    readonly property real axisMonitorWidth: ScreenTools.defaultFontPixelWidth * 32
+    Column {
+        id:                 mainCol
+        anchors.centerIn:   parent
+        spacing:            ScreenTools.defaultFontPixelHeight
+        GridLayout {
+            columns:            2
+            columnSpacing:      ScreenTools.defaultFontPixelWidth
+            rowSpacing:         ScreenTools.defaultFontPixelHeight
+            //---------------------------------------------------------------------
+            //-- Enable Joystick
+            QGCLabel {
+                text:               _activeJoystick ? _activeJoystick.calibrated ? qsTr("Enable joystick input") : qsTr("Enable not allowed (Calibrate First)") : ""
+                Layout.alignment:   Qt.AlignVCenter
+                Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 36
+            }
+            QGCCheckBox {
+                id:             enabledSwitch
+                enabled:        _activeJoystick ? _activeJoystick.calibrated : false
+                onClicked:      activeVehicle.joystickEnabled = checked
+                Component.onCompleted: {
+                    checked = activeVehicle.joystickEnabled
+                }
+                Connections {
+                    target: activeVehicle
+                    onJoystickEnabledChanged: {
+                        enabledSwitch.checked = activeVehicle.joystickEnabled
+                    }
+                }
+                Connections {
+                    target: joystickManager
+                    onActiveJoystickChanged: {
+                        if(_activeJoystick) {
+                            enabledSwitch.checked = Qt.binding(function() { return _activeJoystick.calibrated && activeVehicle.joystickEnabled })
+                        }
+                    }
+                }
+            }
+            //---------------------------------------------------------------------
+            //-- Joystick Selector
+            QGCLabel {
+                text:               qsTr("Active joystick:")
+                Layout.alignment:   Qt.AlignVCenter
+            }
+            QGCComboBox {
+                id:                 joystickCombo
+                width:              ScreenTools.defaultFontPixelWidth * 40
+                Layout.alignment:   Qt.AlignVCenter
+                model:              joystickManager.joystickNames
+                onActivated:        joystickManager.activeJoystickName = textAt(index)
+                Component.onCompleted: {
+                    var index = joystickCombo.find(joystickManager.activeJoystickName)
+                    if (index === -1) {
+                        console.warn(qsTr("Active joystick name not in combo"), joystickManager.activeJoystickName)
+                    } else {
+                        joystickCombo.currentIndex = index
+                    }
+                }
+                Connections {
+                    target: joystickManager
+                    onAvailableJoysticksChanged: {
+                        var index = joystickCombo.find(joystickManager.activeJoystickName)
+                        if (index >= 0) {
+                            joystickCombo.currentIndex = index
+                        }
+                    }
+                }
+            }
+            //---------------------------------------------------------------------
+            //-- RC Mode
+            QGCLabel {
+                text:               qsTr("RC Mode:")
+                Layout.alignment:   Qt.AlignVCenter
+            }
+            Row {
+                spacing:            ScreenTools.defaultFontPixelWidth
+                QGCRadioButton {
+                    text:       "1"
+                    checked:    controller.transmitterMode === 1
+                    enabled:    !controller.calibrating
+                    onClicked:  controller.transmitterMode = 1
+                    anchors.verticalCenter: parent.verticalCenter
+                }
+                QGCRadioButton {
+                    text:       "2"
+                    checked:    controller.transmitterMode === 2
+                    enabled:    !controller.calibrating
+                    onClicked:  controller.transmitterMode = 2
+                    anchors.verticalCenter: parent.verticalCenter
+                }
+                QGCRadioButton {
+                    text:       "3"
+                    checked:    controller.transmitterMode === 3
+                    enabled:    !controller.calibrating
+                    onClicked:  controller.transmitterMode = 3
+                    anchors.verticalCenter: parent.verticalCenter
+                }
+                QGCRadioButton {
+                    text:       "4"
+                    checked:    controller.transmitterMode === 4
+                    enabled:    !controller.calibrating
+                    onClicked:  controller.transmitterMode = 4
+                    anchors.verticalCenter: parent.verticalCenter
+                }
+            }
+        }
+        Row {
+            spacing:                ScreenTools.defaultFontPixelWidth
+            //---------------------------------------------------------------------
+            //-- Axis Monitors
+            Rectangle {
+                id:                 axisRect
+                color:              Qt.rgba(0,0,0,0)
+                border.color:       qgcPal.text
+                border.width:       1
+                radius:             ScreenTools.defaultFontPixelWidth * 0.5
+                width:              axisGrid.width  + (ScreenTools.defaultFontPixelWidth  * 2)
+                height:             axisGrid.height + (ScreenTools.defaultFontPixelHeight * 2)
+                GridLayout {
+                    id:                 axisGrid
+                    columns:            2
+                    columnSpacing:      ScreenTools.defaultFontPixelWidth
+                    rowSpacing:         ScreenTools.defaultFontPixelHeight
+                    anchors.centerIn:   parent
+                    QGCLabel {
+                        text:               activeVehicle.sub ? qsTr("Lateral") : qsTr("Roll")
+                    }
+                    AxisMonitor {
+                        id:                 rollAxis
+                        height:             ScreenTools.defaultFontPixelHeight
+                        width:              axisMonitorWidth
+                        mapped:             controller.rollAxisMapped
+                        reversed:           controller.rollAxisReversed
+                        Connections {
+                            target:             _activeJoystick
+                            onManualControl:    rollAxis.axisValue = roll * 32768.0
+                        }
+                    }
+
+                    QGCLabel {
+                        id:                 pitchLabel
+                        width:              _attitudeLabelWidth
+                        text:               activeVehicle.sub ? qsTr("Forward") : qsTr("Pitch")
+                    }
+                    AxisMonitor {
+                        id:                 pitchAxis
+                        height:             ScreenTools.defaultFontPixelHeight
+                        width:              axisMonitorWidth
+                        mapped:             controller.pitchAxisMapped
+                        reversed:           controller.pitchAxisReversed
+                        Connections {
+                            target:             _activeJoystick
+                            onManualControl:    pitchAxis.axisValue = pitch * 32768.0
+                        }
+                    }
+
+                    QGCLabel {
+                        id:                 yawLabel
+                        width:              _attitudeLabelWidth
+                        text:               qsTr("Yaw")
+                    }
+                    AxisMonitor {
+                        id:                 yawAxis
+                        height:             ScreenTools.defaultFontPixelHeight
+                        width:              axisMonitorWidth
+                        mapped:             controller.yawAxisMapped
+                        reversed:           controller.yawAxisReversed
+                        Connections {
+                            target:             _activeJoystick
+                            onManualControl:    yawAxis.axisValue = yaw * 32768.0
+                        }
+                    }
+
+                    QGCLabel {
+                        id:                 throttleLabel
+                        width:              _attitudeLabelWidth
+                        text:               qsTr("Throttle")
+                    }
+                    AxisMonitor {
+                        id:                 throttleAxis
+                        height:             ScreenTools.defaultFontPixelHeight
+                        width:              axisMonitorWidth
+                        mapped:             controller.throttleAxisMapped
+                        reversed:           controller.throttleAxisReversed
+                        Connections {
+                            target:             _activeJoystick
+                            onManualControl:    throttleAxis.axisValue = _activeJoystick.negativeThrust ? throttle * -32768.0 : (-2 * throttle + 1) * 32768.0
+                        }
+                    }
+
+                    QGCLabel {
+                        id:                 gimbalPitchLabel
+                        width:              _attitudeLabelWidth
+                        text:               qsTr("Gimbal Pitch")
+                        visible:            controller.hasGimbal
+                    }
+                    AxisMonitor {
+                        id:                 gimbalPitchAxis
+                        height:             ScreenTools.defaultFontPixelHeight
+                        width:              axisMonitorWidth
+                        mapped:             controller.gimbalPitchAxisMapped
+                        reversed:           controller.gimbalPitchAxisReversed
+                        visible:            controller.hasGimbal
+                        Connections {
+                            target:             _activeJoystick
+                            onManualControl:    gimbalPitchAxis.axisValue = gimbalPitch * 32768.0
+                        }
+                    }
+
+                    QGCLabel {
+                        id:                 gimbalYawLabel
+                        width:              _attitudeLabelWidth
+                        text:               qsTr("Gimbal Yaw")
+                        visible:            controller.hasGimbal
+                    }
+                    AxisMonitor {
+                        id:                 gimbalYawAxis
+                        height:             ScreenTools.defaultFontPixelHeight
+                        width:              axisMonitorWidth
+                        mapped:             controller.gimbalYawAxisMapped
+                        reversed:           controller.gimbalYawAxisReversed
+                        Connections {
+                            target:             _activeJoystick
+                            onManualControl:    gimbalYawAxis.axisValue = gimbalYaw * 32768.0
+                        }
+                    }
+                }
+            }
+            Rectangle {
+                color:              Qt.rgba(0,0,0,0)
+                border.color:       qgcPal.text
+                border.width:       1
+                radius:             ScreenTools.defaultFontPixelWidth * 0.5
+                width:              axisRect.width
+                height:             axisRect.height
+                Flow {
+                    width:              ScreenTools.defaultFontPixelWidth * 30
+                    spacing:            -1
+                    anchors.centerIn:   parent
+                    Connections {
+                        target:     _activeJoystick
+                        onRawButtonPressedChanged: {
+                            if (buttonMonitorRepeater.itemAt(index)) {
+                                buttonMonitorRepeater.itemAt(index).pressed = pressed
+                            }
+                        }
+                    }
+                    Repeater {
+                        id:         buttonMonitorRepeater
+                        model:      _activeJoystick ? _activeJoystick.totalButtonCount : []
+                        Rectangle {
+                            width:          ScreenTools.defaultFontPixelHeight * 1.5
+                            height:         width
+                            border.width:   1
+                            border.color:   qgcPal.text
+                            color:          pressed ? qgcPal.buttonHighlight : qgcPal.windowShade
+                            property bool pressed
+                            QGCLabel {
+                                anchors.fill:           parent
+                                color:                  pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
+                                horizontalAlignment:    Text.AlignHCenter
+                                verticalAlignment:      Text.AlignVCenter
+                                text:                   modelData
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+
diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc
index 16e80ab..48131bb 100644
--- a/src/uas/UAS.cc
+++ b/src/uas/UAS.cc
@@ -839,8 +839,12 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
 * Set the manual control commands.
 * This can only be done if the system has manual inputs enabled and is armed.
 */
-void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
+void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, float gimbalPitch, float gimbalYaw, quint16 buttons, int joystickMode)
 {
+    //-- TODO
+    Q_UNUSED(gimbalPitch);
+    Q_UNUSED(gimbalYaw);
+
     if (!_vehicle) {
         return;
     }
@@ -997,11 +1001,11 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
         } else if (joystickMode == Vehicle::JoystickModeRC) {
 
             // Save the new manual control inputs
-            manualRollAngle = roll;
-            manualPitchAngle = pitch;
-            manualYawAngle = yaw;
-            manualThrust = thrust;
-            manualButtons = buttons;
+            manualRollAngle     = roll;
+            manualPitchAngle    = pitch;
+            manualYawAngle      = yaw;
+            manualThrust        = thrust;
+            manualButtons       = buttons;
 
             // Store scaling values for all 3 axes
             const float axesScaling = 1.0 * 1000.0;
@@ -1009,19 +1013,22 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
             // Calculate the new commands for roll, pitch, yaw, and thrust
             const float newRollCommand = roll * axesScaling;
             // negate pitch value because pitch is negative for pitching forward but mavlink message argument is positive for forward
-            const float newPitchCommand = -pitch * axesScaling;
-            const float newYawCommand = yaw * axesScaling;
+            const float newPitchCommand  = -pitch * axesScaling;
+            const float newYawCommand    = yaw * axesScaling;
             const float newThrustCommand = thrust * axesScaling;
 
-            //qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
-
             // Send the MANUAL_COMMAND message
-            mavlink_msg_manual_control_pack_chan(mavlink->getSystemId(),
-                                                 mavlink->getComponentId(),
-                                                 _vehicle->priorityLink()->mavlinkChannel(),
-                                                 &message,
-                                                 this->uasId,
-                                                 newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
+            mavlink_msg_manual_control_pack_chan(
+                static_cast<uint8_t>(mavlink->getSystemId()),
+                static_cast<uint8_t>(mavlink->getComponentId()),
+                _vehicle->priorityLink()->mavlinkChannel(),
+                &message,
+                static_cast<uint8_t>(this->uasId),
+                static_cast<int16_t>(newPitchCommand),
+                static_cast<int16_t>(newRollCommand),
+                static_cast<int16_t>(newThrustCommand),
+                static_cast<int16_t>(newYawCommand),
+                buttons);
         }
 
         _vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
diff --git a/src/uas/UAS.h b/src/uas/UAS.h
index 39d842e..145345e 100644
--- a/src/uas/UAS.h
+++ b/src/uas/UAS.h
@@ -263,7 +263,7 @@ public slots:
 #endif
 
     /** @brief Set the values for the manual control of the vehicle */
-    void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode);
+    void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, float gimbalPitch, float gimbalYaw, quint16 buttons, int joystickMode);
 
     /** @brief Set the values for the 6dof manual control of the vehicle */
 #ifndef __mobile__