From 26e4f8ccb3deee2aabea00bc23b26e0e722f4f25 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 31 Oct 2017 18:01:33 +1100 Subject: [PATCH] Plane: fixed GUIDED loiter with Q_RTL_MODE=1 this was broken by the recent RTL_RADIUS changes thanks to Nick for noticing this! --- ArduPlane/navigation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index e53d03a798..0b874bea1f 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -189,7 +189,7 @@ void Plane::update_loiter(uint16_t radius) control_mode == AUTO && !auto_state.no_crosstrack && get_distance(current_loc, next_WP_loc) > radius*3) || - (quadplane.available() && quadplane.rtl_mode == 1)) { + (control_mode == RTL && quadplane.available() && quadplane.rtl_mode == 1)) { /* if never reached loiter point and using crosstrack and somewhat far away from loiter point navigate to it like in auto-mode for normal crosstrack behavior