Copter: remain landed until throttle output above 25 percent

This commit is contained in:
Randy Mackay 2014-07-17 18:16:55 +09:00
parent edd7334544
commit 11678ba936
1 changed files with 1 additions and 1 deletions

View File

@ -202,7 +202,7 @@ static bool update_land_detector()
land_detector = 0;
}
}
} else if (g.rc_3.control_in != 0 || failsafe.radio) {
} else if ((motors.get_throttle_out() >= get_non_takeoff_throttle()) || failsafe.radio) {
// we've sensed movement up or down so reset land_detector
land_detector = 0;
if(ap.land_complete) {