7 yaw when armed option changed so overridable by user

This commit is contained in:
Dr Gareth Owen 2013-05-24 11:14:06 +09:00 committed by Randy Mackay
parent a22f5e3bc4
commit 1aca66460e

View File

@ -1519,6 +1519,12 @@ void update_yaw_mode(void)
// changes yaw to be same as when quad was armed
nav_yaw = get_yaw_slew(nav_yaw, initial_simple_bearing, AUTO_YAW_SLEW_RATE);
get_stabilize_yaw(nav_yaw);
// if there is any pilot input, switch to YAW_HOLD mode for the next iteration
if( g.rc_4.control_in != 0 ) {
set_yaw_mode(YAW_HOLD);
}
break;
}
}