mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
TradHeli - fix to set motor_auto_armed = true if throttle > 0. Required to let ALT_HOLD work!
This commit is contained in:
parent
b6b2606442
commit
3e19c219e3
@ -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();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user