Browse Source

APM: show real raw RC input, not mixed input

this makes it easier to diagnose elevon mixing issues
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
6e9abb616a
  1. 16
      ArduPlane/GCS_Mavlink.pde

16
ArduPlane/GCS_Mavlink.pde

@ -310,14 +310,14 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan)
chan, chan,
millis(), millis(),
0, // port 0, // port
g.channel_roll.radio_in, APM_RC.InputCh(CH_1),
g.channel_pitch.radio_in, APM_RC.InputCh(CH_2),
g.channel_throttle.radio_in, APM_RC.InputCh(CH_3),
g.channel_rudder.radio_in, APM_RC.InputCh(CH_4),
g.rc_5.radio_in, // XXX currently only 4 RC channels defined APM_RC.InputCh(CH_5),
g.rc_6.radio_in, APM_RC.InputCh(CH_6),
g.rc_7.radio_in, APM_RC.InputCh(CH_7),
g.rc_8.radio_in, APM_RC.InputCh(CH_8),
receiver_rssi); receiver_rssi);
} }

Loading…
Cancel
Save