Browse Source

Copter: landing_complete stays true until thr is raised

The idea of the fix is we can't leave land while throttle is 0 and then
we ignore the baro and it's disturbances.
mission-4.1.18
Ju1ien 11 years ago committed by Randy Mackay
parent
commit
311bba1419
  1. 2
      ArduCopter/Attitude.pde

2
ArduCopter/Attitude.pde

@ -1126,7 +1126,7 @@ static bool update_land_detector() @@ -1126,7 +1126,7 @@ static bool update_land_detector()
land_detector = 0;
}
}
}else{
}else if (g.rc_3.control_in != 0 || failsafe.radio){ // zero throttle locks land_complete as true
// we've sensed movement up or down so reset land_detector
land_detector = 0;
if(ap.land_complete) {

Loading…
Cancel
Save