diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 14cd542c4c..6d2763d494 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -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: {