AP_Math: fixed get_distance() function

This commit is contained in:
Andrew Tridgell 2012-12-20 11:48:58 +11:00
parent 087bf380c0
commit d8bed0c2aa

View File

@ -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