From 37b3f48786bf2acd5d87f290b55330eb70b93690 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 11 May 2022 13:40:48 +1000 Subject: [PATCH] ArduPlane: support *10 multipler when storing/retrieving radius in NAV_LOITER_TURNS --- ArduPlane/commands_logic.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index b5c621fae9..c33bceef44 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -713,6 +713,10 @@ bool Plane::verify_loiter_turns(const AP_Mission::Mission_Command &cmd) { bool result = false; uint16_t radius = HIGHBYTE(cmd.p1); + if (cmd.type_specific_bits & (1U<<0)) { + // special storage handling allows for larger radii + radius *= 10; + } update_loiter(radius); // LOITER_TURNS makes no sense as VTOL