Copter: add land_complete to fence disarm check

This commit is contained in:
Jonathan Challinger 2014-10-10 02:08:26 -07:00 committed by Randy Mackay
parent 9ced648479
commit f64f155c3a
1 changed files with 1 additions and 1 deletions

View File

@ -30,7 +30,7 @@ void fence_check()
// disarm immediately if we think we are on the ground
// don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
if(manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0)){
if(ap.land_complete || manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0)){
init_disarm_motors();
}else{
// if we are within 100m of the fence, RTL