ArduCopter: maintain loiter control even below 1m while landing

This commit is contained in:
rmackay9 2012-12-06 12:40:53 +09:00
parent 2dd4694eef
commit 75401756f2
1 changed files with 0 additions and 11 deletions

View File

@ -358,17 +358,6 @@ static bool verify_takeoff()
// verify_land - returns true if landing has been completed
static bool verify_land()
{
// loiter above 3m
if(current_loc.alt > 300) {
wp_control = LOITER_MODE;
}
// turn off loiter below 1m
// To-Do: instead of turning off loiter we should make loiter less aggressive
if(current_loc.alt < 100 ) {
wp_control = NO_NAV_MODE;
}
// rely on THROTTLE_LAND mode to correctly update landing status
return ap.land_complete;
}