ArduCopter setup.pde: translate from CH_ to MOT_ notation

This commit is contained in:
Pat Hickey 2012-01-01 15:28:49 -05:00
parent 91bc2698a8
commit 6a4442557c
1 changed files with 8 additions and 8 deletions

View File

@ -1102,16 +1102,16 @@ init_esc()
read_radio();
delay(100);
dancing_light();
APM_RC.OutputCh(CH_1, g.rc_3.radio_in);
APM_RC.OutputCh(CH_2, g.rc_3.radio_in);
APM_RC.OutputCh(CH_3, g.rc_3.radio_in);
APM_RC.OutputCh(CH_4, g.rc_3.radio_in);
APM_RC.OutputCh(CH_7, g.rc_3.radio_in);
APM_RC.OutputCh(CH_8, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_1, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_2, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_3, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_4, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_5, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_6, g.rc_3.radio_in);
#if FRAME_CONFIG == OCTA_FRAME
APM_RC.OutputCh(CH_10, g.rc_3.radio_in);
APM_RC.OutputCh(CH_11, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_7, g.rc_3.radio_in);
APM_RC.OutputCh(MOT_8, g.rc_3.radio_in);
#endif
}