APM: use OutputCh_current() in MAVLink servo logging

this gives a more accurate picture of what is actually happening with
the servos
This commit is contained in:
Andrew Tridgell 2012-04-23 12:30:16 +10:00
parent e8f8115a8f
commit 8e6fdb8981
1 changed files with 8 additions and 8 deletions

View File

@ -418,14 +418,14 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
chan, chan,
micros(), micros(),
0, // port 0, // port
g.channel_roll.radio_out, APM_RC.OutputCh_current(0),
g.channel_pitch.radio_out, APM_RC.OutputCh_current(1),
g.channel_throttle.radio_out, APM_RC.OutputCh_current(2),
g.channel_rudder.radio_out, APM_RC.OutputCh_current(3),
g.rc_5.radio_out, // XXX currently only 4 RC channels defined APM_RC.OutputCh_current(4),
g.rc_6.radio_out, APM_RC.OutputCh_current(5),
g.rc_7.radio_out, APM_RC.OutputCh_current(6),
g.rc_8.radio_out); APM_RC.OutputCh_current(7));
} }
static void NOINLINE send_vfr_hud(mavlink_channel_t chan) static void NOINLINE send_vfr_hud(mavlink_channel_t chan)