From d8bed0c2aac5751fc092d8e9fe0048525ad45985 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 20 Dec 2012 11:48:58 +1100 Subject: [PATCH] AP_Math: fixed get_distance() function --- libraries/AP_Math/location.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Math/location.cpp b/libraries/AP_Math/location.cpp index ef33f7fe4b..8971b19d60 100644 --- a/libraries/AP_Math/location.cpp +++ b/libraries/AP_Math/location.cpp @@ -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