mirror of https://github.com/ArduPilot/ardupilot
Plane: Remove the use of RTL_RADIUS from LOITER_UNLIM mission items
This commit is contained in:
parent
645ebe21e9
commit
43526e718e
|
@ -657,14 +657,8 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
bool Plane::verify_loiter_unlim(const AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
if (cmd.p1 <= 1 && abs(g.rtl_radius) > 1) {
|
||||
// if mission radius is 0,1, and rtl_radius is valid, use rtl_radius.
|
||||
loiter.direction = (g.rtl_radius < 0) ? -1 : 1;
|
||||
update_loiter(abs(g.rtl_radius));
|
||||
} else {
|
||||
// else use mission radius
|
||||
update_loiter(cmd.p1);
|
||||
}
|
||||
// else use mission radius
|
||||
update_loiter(cmd.p1);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue