mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: bug fix to reset yaw target when zero and when in stabilize or acro mode.
This commit is contained in:
parent
176e6fdd68
commit
c091c8e0e6
|
@ -1591,7 +1591,7 @@ void update_yaw_mode(void)
|
|||
}else{
|
||||
// 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) )
|
||||
if(motors.armed() == false || ((g.rc_3.control_in == 0) && (control_mode <= ACRO) && !failsafe))
|
||||
nav_yaw = ahrs.yaw_sensor;
|
||||
|
||||
g.rc_4.servo_out = get_stabilize_yaw(nav_yaw);
|
||||
|
|
Loading…
Reference in New Issue