From 5cdee95516cc618a2e0dc4f0e338c35ed6deb0d4 Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Thu, 19 Jan 2012 20:20:50 -0800 Subject: [PATCH] ArduPlane: Call APM_RC.enable_out for all channels in init_rc_out. --- ArduPlane/radio.pde | 21 ++++++++++----------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index e0a8b870b9..ac4b802ef8 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -33,18 +33,17 @@ static void init_rc_in() static void init_rc_out() { - APM_RC.OutputCh(CH_1, g.channel_roll.radio_trim); // Initialization of servo outputs - APM_RC.OutputCh(CH_2, g.channel_pitch.radio_trim); - APM_RC.OutputCh(CH_3, g.channel_throttle.radio_min); - APM_RC.OutputCh(CH_4, g.channel_rudder.radio_trim); - - APM_RC.OutputCh(CH_5, g.rc_5.radio_trim); - APM_RC.OutputCh(CH_6, g.rc_6.radio_trim); - APM_RC.OutputCh(CH_7, g.rc_7.radio_trim); - APM_RC.OutputCh(CH_8, g.rc_8.radio_trim); - APM_RC.Init( &isr_registry ); // APM Radio initialization + APM_RC.enable_out(CH_1); + APM_RC.enable_out(CH_2); + APM_RC.enable_out(CH_3); + APM_RC.enable_out(CH_4); + APM_RC.enable_out(CH_5); + APM_RC.enable_out(CH_6); + APM_RC.enable_out(CH_7); + APM_RC.enable_out(CH_8); + APM_RC.OutputCh(CH_1, g.channel_roll.radio_trim); // Initialization of servo outputs APM_RC.OutputCh(CH_2, g.channel_pitch.radio_trim); APM_RC.OutputCh(CH_3, g.channel_throttle.radio_min); @@ -53,7 +52,7 @@ static void init_rc_out() APM_RC.OutputCh(CH_5, g.rc_5.radio_trim); APM_RC.OutputCh(CH_6, g.rc_6.radio_trim); APM_RC.OutputCh(CH_7, g.rc_7.radio_trim); - APM_RC.OutputCh(CH_8, g.rc_8.radio_trim); + APM_RC.OutputCh(CH_8, g.rc_8.radio_trim); } static void read_radio()