Copter: make landing detector more strict

Made more strict by requiring 50 consecutive iterations where the climb
rate is below +- 40cm/s.  Previously it was 50 cumulative.

Removed check of failsafe.radio when clearing the land flag because it
could result in the vehicle taking off if the user picked it up.
This commit is contained in:
Randy Mackay 2014-08-25 17:25:32 +09:00
parent cf0741f6fd
commit 63d0cddfa4
1 changed files with 6 additions and 8 deletions

View File

@ -188,13 +188,13 @@ static float get_throttle_land()
} }
// update_land_detector - checks if we have landed and updates the ap.land_complete flag // update_land_detector - checks if we have landed and updates the ap.land_complete flag
// returns true if we have landed // called at 50hz
static bool update_land_detector() static void update_land_detector()
{ {
// detect whether we have landed by watching for low climb rate and minimum throttle // detect whether we have landed by watching for low climb rate and minimum throttle
if (abs(climb_rate) < 40 && motors.limit.throttle_lower) { if (abs(climb_rate) < 40 && motors.limit.throttle_lower) {
if (!ap.land_complete) { if (!ap.land_complete) {
// run throttle controller if accel based throttle controller is enabled and active (active means it has been given a target) // increase counter until we hit the trigger then set land complete flag
if( land_detector < LAND_DETECTOR_TRIGGER) { if( land_detector < LAND_DETECTOR_TRIGGER) {
land_detector++; land_detector++;
}else{ }else{
@ -202,16 +202,14 @@ static bool update_land_detector()
land_detector = 0; land_detector = 0;
} }
} }
} else if ((motors.get_throttle_out() > get_non_takeoff_throttle()) || failsafe.radio) { } else {
// we've sensed movement up or down so reset land_detector // we've sensed movement up or down so reset land_detector
land_detector = 0; land_detector = 0;
if(ap.land_complete) { // if throttle output is high then clear landing flag
if (motors.get_throttle_out() > get_non_takeoff_throttle()) {
set_land_complete(false); set_land_complete(false);
} }
} }
// return current state of landing
return ap.land_complete;
} }
// land_do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch // land_do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch