mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed loiter.direction for VTOL approach
ensure the direction is setup correctly for both CW and CCW
This commit is contained in:
parent
4e54f84c10
commit
1c87a48774
|
@ -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