From fdd20830d6e8fe0edfa3defc40facf1c0cbac78d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 12 Jul 2016 15:08:06 +1000 Subject: [PATCH] SITL: use flaps for collective on helis in X-Plane 10 works for more helis --- libraries/SITL/SIM_XPlane.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index 25db18664f..c8fd8c1871 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -172,10 +172,16 @@ bool XPlane::receive_data(void) break; case AoA: - case Trim: // ignored break; + case Trim: + if (heli_frame) { + // use flaps for collective as no direct collective data input + rcin[2] = data[4]; + } + break; + case PitchRollHeading: { float roll, pitch, yaw; pitch = radians(data[1]); @@ -218,10 +224,7 @@ bool XPlane::receive_data(void) break; case ThrottleCommand: { - if (heli_frame) { - // on helis we setup the joystick to use "throttle2" for collective input - rcin[2] = data[2]; - } else { + if (!heli_frame) { /* getting joystick throttle input is very weird. The * problem is that XPlane sends the ThrottleCommand packet * both for joystick throttle input and for throttle that