APM: prevent crosstrack from takeoff point after takeoff completion

This commit is contained in:
Andrew Tridgell 2012-09-02 11:28:32 +10:00
parent dec12c7370
commit f26b9ab286
1 changed files with 1 additions and 0 deletions

View File

@ -304,6 +304,7 @@ static bool verify_takeoff()
if (current_loc.alt > takeoff_altitude) {
hold_course = -1;
takeoff_complete = true;
next_WP = current_loc;
return true;
} else {
return false;