Browse Source

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

apm_2208
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
d5fdc2027f
  1. 4
      ArduPlane/commands_logic.cpp

4
ArduPlane/commands_logic.cpp

@ -713,6 +713,10 @@ bool Plane::verify_loiter_turns(const AP_Mission::Mission_Command &cmd) @@ -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

Loading…
Cancel
Save