mirror of https://github.com/ArduPilot/ardupilot
adjust tri frame output to not output 4th motor
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1567 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
3443a7817d
commit
f57887ee4a
|
@ -293,7 +293,8 @@ setup_motors(uint8_t argc, const Menu::arg *argv)
|
||||||
APM_RC.OutputCh(CH_1, rc_3.radio_in);
|
APM_RC.OutputCh(CH_1, rc_3.radio_in);
|
||||||
APM_RC.OutputCh(CH_2, rc_3.radio_in);
|
APM_RC.OutputCh(CH_2, rc_3.radio_in);
|
||||||
APM_RC.OutputCh(CH_3, rc_3.radio_in);
|
APM_RC.OutputCh(CH_3, rc_3.radio_in);
|
||||||
APM_RC.OutputCh(CH_4, rc_3.radio_in);
|
if(frame_type != TRI_FRAME)
|
||||||
|
APM_RC.OutputCh(CH_4, rc_3.radio_in);
|
||||||
}else{
|
}else{
|
||||||
APM_RC.OutputCh(CH_1, motor_out[RIGHT]);
|
APM_RC.OutputCh(CH_1, motor_out[RIGHT]);
|
||||||
APM_RC.OutputCh(CH_2, motor_out[LEFT]);
|
APM_RC.OutputCh(CH_2, motor_out[LEFT]);
|
||||||
|
|
Loading…
Reference in New Issue