Copter: bug fix to land-detector
vehicle should become un-landed only when throttle out is above the get-non-throttle-takeoff value
This commit is contained in:
parent
c7ba44db2d
commit
279aff87f2
@ -202,7 +202,7 @@ static bool update_land_detector()
|
||||
land_detector = 0;
|
||||
}
|
||||
}
|
||||
} else if ((motors.get_throttle_out() >= get_non_takeoff_throttle()) || 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) {
|
||||
|
Loading…
Reference in New Issue
Block a user