Plane: fixed loiter.direction for VTOL approach

ensure the direction is setup correctly for both CW and CCW
This commit is contained in:
Andrew Tridgell 2023-01-15 10:36:56 +11:00
parent 58de912681
commit e72a46c092
1 changed files with 2 additions and 0 deletions

View File

@ -1019,6 +1019,8 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
const int8_t direction = is_negative(radius) ? -1 : 1;
const float abs_radius = fabsf(radius);
loiter.direction = direction;
switch (vtol_approach_s.approach_stage) {
case RTL:
{