mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: FW approach: use abs value for loiter sum check
This commit is contained in:
parent
2bda3c44c6
commit
98887a984b
@ -1044,7 +1044,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
|
||||
// require an angle total of at least 2 centidegrees, due to special casing of 1 centidegree
|
||||
if (((fabsf(cmd.content.location.get_distance(current_loc) - abs_radius) > 5.0f) &&
|
||||
(cmd.content.location.get_distance(current_loc) < abs_radius)) ||
|
||||
(loiter.sum_cd < 2)) {
|
||||
(labs(loiter.sum_cd) < 2)) {
|
||||
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user