diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index c42df6685f..0e5a25f16c 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -262,6 +262,10 @@ bool XPlane::receive_data(void) break; case Generator: + /* + in order to get interlock switch on helis we map the + "generator1 on/off" function of XPlane 10 to channel 8. + */ rcin_chan_count = 8; rcin[7] = data[1]; break;