mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
AP_Math: prevent negative longitude scaling
for crazy locations
This commit is contained in:
parent
7752196628
commit
b92873cab1
@ -44,6 +44,7 @@ float longitude_scale(const struct Location &loc)
|
||||
return scale;
|
||||
}
|
||||
scale = cosf(loc.lat * 1.0e-7f * DEG_TO_RAD);
|
||||
scale = constrain_float(scale, 0.01f, 1.0f);
|
||||
last_lat = loc.lat;
|
||||
return scale;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user