mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
removed some unused code, made output min by default
This commit is contained in:
parent
13e2ecf096
commit
bcfbdeb4d3
@ -54,11 +54,6 @@ static void init_rc_in()
|
||||
|
||||
static void init_rc_out()
|
||||
{
|
||||
#if ARM_AT_STARTUP == 1
|
||||
motor_armed = 1;
|
||||
#endif
|
||||
|
||||
|
||||
APM_RC.Init(); // APM Radio initialization
|
||||
init_motors_out();
|
||||
|
||||
@ -78,9 +73,7 @@ static void init_rc_out()
|
||||
if(g.esc_calibrate == 1)
|
||||
return;
|
||||
|
||||
if(g.rc_3.radio_min <= 1200){
|
||||
output_min();
|
||||
}
|
||||
output_min();
|
||||
|
||||
for(byte i = 0; i < 5; i++){
|
||||
delay(20);
|
||||
|
Loading…
Reference in New Issue
Block a user