mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM: prevent crosstrack from takeoff point after takeoff completion
This commit is contained in:
parent
dec12c7370
commit
f26b9ab286
@ -304,6 +304,7 @@ static bool verify_takeoff()
|
|||||||
if (current_loc.alt > takeoff_altitude) {
|
if (current_loc.alt > takeoff_altitude) {
|
||||||
hold_course = -1;
|
hold_course = -1;
|
||||||
takeoff_complete = true;
|
takeoff_complete = true;
|
||||||
|
next_WP = current_loc;
|
||||||
return true;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user