From c091c8e0e6fdb374cf8bf7dfaeb5716c68cbcbc6 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Wed, 1 Aug 2012 12:15:02 +0900 Subject: [PATCH] ArduCopter: bug fix to reset yaw target when zero and when in stabilize or acro mode. --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index f763da808f..3fde6df418 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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);