mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: reset target yaw when throttle is zero (except if failsafe has been triggered)
This commit is contained in:
parent
717d0d25d4
commit
38ff381620
|
@ -1589,7 +1589,9 @@ void update_yaw_mode(void)
|
||||||
nav_yaw = ahrs.yaw_sensor;
|
nav_yaw = ahrs.yaw_sensor;
|
||||||
}
|
}
|
||||||
}else{
|
}else{
|
||||||
if(motors.armed() == false)
|
// reset target yaw to current yaw if the motors are disarmed or throttle is zero
|
||||||
|
// Note: we do not want to reset yaw if failsafe has been triggered even though throttle maybe zero (in fact, normally throttle is zero in failsafe)
|
||||||
|
if(motors.armed() == false || (g.rc_3.control_in == 0 && !failsafe) )
|
||||||
nav_yaw = ahrs.yaw_sensor;
|
nav_yaw = ahrs.yaw_sensor;
|
||||||
|
|
||||||
g.rc_4.servo_out = get_stabilize_yaw(nav_yaw);
|
g.rc_4.servo_out = get_stabilize_yaw(nav_yaw);
|
||||||
|
|
Loading…
Reference in New Issue