mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: call update_loiter before determining whether to fly home or not
we are calling "reached_loiter_target" as part of our checks as to whether to fly home or not.
We need to call update_loiter so the L1 controller can update its internal state for the new waypoint which do_RTL has set. Depending on location (but typically), that will mean that L1's reached_loiter_target() will then return false, so we fly home.
This bug was affected by f8d7be5e43
. Any sort of altitude error greater than 10m would delay us entering the landing sequence, allowing the L1 controller to update its state.
This commit is contained in:
parent
593aeb3a13
commit
c28248b963
@ -95,6 +95,13 @@ void ModeRTL::navigate()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
uint16_t radius = abs(plane.g.rtl_radius);
|
||||||
|
if (radius > 0) {
|
||||||
|
plane.loiter.direction = (plane.g.rtl_radius < 0) ? -1 : 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
plane.update_loiter(radius);
|
||||||
|
|
||||||
if (!plane.auto_state.checked_for_autoland) {
|
if (!plane.auto_state.checked_for_autoland) {
|
||||||
if ((plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) ||
|
if ((plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) ||
|
||||||
(plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START &&
|
(plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START &&
|
||||||
@ -116,13 +123,6 @@ void ModeRTL::navigate()
|
|||||||
plane.auto_state.checked_for_autoland = true;
|
plane.auto_state.checked_for_autoland = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t radius = abs(plane.g.rtl_radius);
|
|
||||||
if (radius > 0) {
|
|
||||||
plane.loiter.direction = (plane.g.rtl_radius < 0) ? -1 : 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
plane.update_loiter(radius);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user