Copter: relax altitude check in verify_takeoff

Previously we checked if the alt > target_alt but because there is
little to no overshoot with the new accel based alt controller this
check was failing for some users.
This commit is contained in:
Randy Mackay 2013-01-14 12:40:59 +09:00 committed by rmackay9
parent 4c4b6afaff
commit 76f032160c
1 changed files with 1 additions and 1 deletions

View File

@ -364,7 +364,7 @@ static bool verify_takeoff()
return false;
}
// are we above our target altitude?
return (current_loc.alt > next_WP.alt);
return (alt_change_flag == REACHED_ALT);
}
// verify_land - returns true if landing has been completed