mirror of https://github.com/ArduPilot/ardupilot
Location Lib : Abs was overflowing causing bad comparison
This commit is contained in:
parent
4d5d16720b
commit
a66e43aff1
|
@ -31,7 +31,7 @@ static float longitude_scale(const struct Location *loc)
|
|||
{
|
||||
static int32_t last_lat;
|
||||
static float scale = 1.0;
|
||||
if (abs(last_lat - loc->lat) < 100000) {
|
||||
if (labs(last_lat - loc->lat) < 100000) {
|
||||
// we are within 0.01 degrees (about 1km) of the
|
||||
// same latitude. We can avoid the cos() and return
|
||||
// the same scale factor.
|
||||
|
|
Loading…
Reference in New Issue