mirror of https://github.com/ArduPilot/ardupilot
ArduCopter radio.pde: translate CH_ to MOT_ outputs
This commit is contained in:
parent
8d4db05f50
commit
38c2a052be
|
@ -55,8 +55,8 @@ static void init_rc_out()
|
|||
init_motors_out();
|
||||
|
||||
// this is the camera pitch5 and roll6
|
||||
APM_RC.OutputCh(CH_5, 1500);
|
||||
APM_RC.OutputCh(CH_6, 1500);
|
||||
APM_RC.OutputCh(CH_CAM_PITCH, 1500);
|
||||
APM_RC.OutputCh(CH_CAM_ROLL, 1500);
|
||||
|
||||
for(byte i = 0; i < 5; i++){
|
||||
delay(20);
|
||||
|
@ -103,18 +103,18 @@ void output_min()
|
|||
#if FRAME_CONFIG == HELI_FRAME
|
||||
heli_move_servos_to_mid();
|
||||
#else
|
||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min); // Initialization of servo outputs
|
||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); // Initialization of servo outputs
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
#endif
|
||||
|
||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
|
||||
#if FRAME_CONFIG == OCTA_FRAME
|
||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue