mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: fixed loiter.direction for VTOL approach
ensure the direction is setup correctly for both CW and CCW
This commit is contained in:
parent
2b2bd2b85b
commit
9b2c7a90e7
@ -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:
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user