mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed negative loiter radius values
This commit is contained in:
parent
b7135175c9
commit
62574b35b5
|
@ -139,7 +139,7 @@ void Plane::update_loiter(uint16_t radius)
|
||||||
{
|
{
|
||||||
if (radius <= 1) {
|
if (radius <= 1) {
|
||||||
// if radius is <=1 then use the general loiter radius. if it's small, use default
|
// if radius is <=1 then use the general loiter radius. if it's small, use default
|
||||||
radius = (abs(g.loiter_radius <= 1)) ? LOITER_RADIUS_DEFAULT : abs(g.loiter_radius);
|
radius = (abs(g.loiter_radius) <= 1) ? LOITER_RADIUS_DEFAULT : abs(g.loiter_radius);
|
||||||
loiter.direction = (g.loiter_radius < 0) ? -1 : 1;
|
loiter.direction = (g.loiter_radius < 0) ? -1 : 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue