ArduPlane: support *10 multipler when storing/retrieving radius in NAV_LOITER_TURNS

This commit is contained in:
Peter Barker 2022-05-11 13:40:48 +10:00 committed by Andrew Tridgell
parent 087d5ec6c7
commit d5fdc2027f
1 changed files with 4 additions and 0 deletions

View File

@ -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