Plane: if pilot gives aileron input then disable ground steering

otherwise it would be very tricky to do a low pass!
This commit is contained in:
Andrew Tridgell 2013-10-04 08:20:32 +10:00
parent d32e58db84
commit 536fbb4a30
1 changed files with 1 additions and 1 deletions

View File

@ -195,7 +195,7 @@ static void stabilize_stick_mixing_fbw()
*/ */
static void stabilize_yaw(float speed_scaler) static void stabilize_yaw(float speed_scaler)
{ {
bool ground_steering = fabsf(relative_altitude()) < g.ground_steer_alt; bool ground_steering = (channel_roll->control_in == 0 && fabsf(relative_altitude()) < g.ground_steer_alt);
if (steer_state.hold_course_cd != -1 && ground_steering) { if (steer_state.hold_course_cd != -1 && ground_steering) {
calc_nav_yaw_course(); calc_nav_yaw_course();