From 735d6f69b3f882919f4183fa735eb1bee429da82 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Sun, 29 Nov 2020 16:36:15 -0300 Subject: [PATCH] VirtualJoystick: remove sub from yAxisPositiveRangeOnly condition (#9204) Sub currently handles throttle in the 0-1000 range https://github.com/ArduPilot/ardupilot/issues/8818 --- src/FlightDisplay/VirtualJoystick.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/FlightDisplay/VirtualJoystick.qml b/src/FlightDisplay/VirtualJoystick.qml index 97c93b3..64abea8 100644 --- a/src/FlightDisplay/VirtualJoystick.qml +++ b/src/FlightDisplay/VirtualJoystick.qml @@ -41,7 +41,7 @@ Item { anchors.bottom: parent.bottom width: parent.height height: parent.height - yAxisPositiveRangeOnly: _activeVehicle && !_activeVehicle.rover && !_activeVehicle.sub + yAxisPositiveRangeOnly: _activeVehicle && !_activeVehicle.rover yAxisReCenter: autoCenterThrottle }