mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: support *10 multipler when storing/retrieving radius in NAV_LOITER_TURNS
This commit is contained in:
parent
d435181756
commit
37b3f48786
|
@ -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…
Reference in New Issue