Browse Source

Copter: bug fix to land-detector

vehicle should become un-landed only when throttle out is above the
get-non-throttle-takeoff value
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
279aff87f2
  1. 2
      ArduCopter/control_land.pde

2
ArduCopter/control_land.pde

@ -202,7 +202,7 @@ static bool update_land_detector() @@ -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…
Cancel
Save