added ch7,8 to init for hexa quads

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1584 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-02-01 05:01:19 +00:00
parent 87782a44af
commit aecc9db68e
1 changed files with 8 additions and 0 deletions

View File

@ -36,12 +36,20 @@ void init_rc_out()
APM_RC.OutputCh(CH_3, rc_3.radio_min);
APM_RC.OutputCh(CH_4, rc_3.radio_min);
APM_RC.OutputCh(CH_7, rc_3.radio_min);
APM_RC.OutputCh(CH_8, rc_3.radio_min);
APM_RC.Init(); // APM Radio initialization
APM_RC.OutputCh(CH_1, rc_3.radio_min); // Initialization of servo outputs
APM_RC.OutputCh(CH_2, rc_3.radio_min);
APM_RC.OutputCh(CH_3, rc_3.radio_min);
APM_RC.OutputCh(CH_4, rc_3.radio_min);
APM_RC.OutputCh(CH_7, rc_3.radio_min);
APM_RC.OutputCh(CH_8, rc_3.radio_min);
}
void read_radio()