mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: fixed a condition where takeoff switches to land
This commit is contained in:
parent
537f22cdd1
commit
3dd47adafe
@ -858,6 +858,8 @@ void Plane::update_flight_stage(void)
|
||||
bool below_prev_WP = current_loc.alt < prev_WP_loc.alt;
|
||||
if ((path_progress > 0.15f && lined_up && below_prev_WP) || path_progress > 0.5f) {
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_LAND_APPROACH);
|
||||
} else {
|
||||
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user