Skip to content

Commit

Permalink
Plane: call update_loiter before determining whether to fly home or not
Browse files Browse the repository at this point in the history
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 f8d7be5 .  Any sort of altitude error greater than 10m would delay us entering the landing sequence, allowing the L1 controller to update its state.
  • Loading branch information
peterbarker authored and tridge committed Apr 10, 2024
1 parent ae3c74b commit 39c87c0
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions ArduPlane/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,13 @@ void ModeRTL::navigate()
}
#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.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) ||
(plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START &&
Expand All @@ -116,13 +123,6 @@ void ModeRTL::navigate()
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
Expand Down

0 comments on commit 39c87c0

Please sign in to comment.