mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Location Lib. Potential fix for bad angle and distance calcs.
last_lat changed to int32_t since it can be negative.
This commit is contained in:
parent
93c644fd0f
commit
555e26d5fa
@ -29,7 +29,7 @@
|
||||
|
||||
static float longitude_scale(const struct Location *loc)
|
||||
{
|
||||
static uint32_t last_lat;
|
||||
static int32_t last_lat;
|
||||
static float scale = 1.0;
|
||||
if (abs(last_lat - loc->lat) < 100000) {
|
||||
// we are within 0.01 degrees (about 1km) of the
|
||||
@ -38,6 +38,7 @@ static float longitude_scale(const struct Location *loc)
|
||||
return scale;
|
||||
}
|
||||
scale = cos((fabs((float)loc->lat)/1.0e7) * 0.0174532925);
|
||||
last_lat = loc->lat;
|
||||
return scale;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user