TradHeli - fix to set motor_auto_armed = true if throttle > 0. Required to let ALT_HOLD work!

This commit is contained in:
rmackay9 2011-09-25 12:30:37 +09:00
parent 7f1f6e519b
commit ddb4de1949

View File

@ -159,7 +159,12 @@ static void output_motors_armed()
// for helis - armed or disarmed we allow servos to move
static void output_motors_disarmed()
{
//heli_move_servos_to_mid();
if(g.rc_3.control_in > 0){
// we have pushed up the throttle
// remove safety
motor_auto_armed = true;
}
output_motors_armed();
}