mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Math: fixed get_distance() function
This commit is contained in:
parent
087bf380c0
commit
d8bed0c2aa
@ -53,7 +53,7 @@ float get_distance(const struct Location *loc1, const struct Location *loc2)
|
||||
return -1;
|
||||
float dlat = (float)(loc2->lat - loc1->lat);
|
||||
float dlong = ((float)(loc2->lng - loc1->lng)) * longitude_scale(loc2);
|
||||
return pythagorous2(dlat, dlong);
|
||||
return pythagorous2(dlat, dlong) * 0.01113195;
|
||||
}
|
||||
|
||||
// return distance in centimeters to between two locations, or -1 if
|
||||
|
Loading…
Reference in New Issue
Block a user