mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
Emile's Fixes
This commit is contained in:
parent
4483f19f85
commit
c7c16a5b0f
@ -168,7 +168,6 @@ static void output_motor_test()
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
@ -199,10 +198,7 @@ static void output_motor_test()
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
}
|
||||
|
||||
} else { /* PLUS_FRAME */
|
||||
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
@ -234,8 +230,6 @@ static void output_motor_test()
|
||||
delay(300);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
|
Loading…
Reference in New Issue
Block a user