mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Math: added get_distance_cm() to return in centimeters
This commit is contained in:
parent
165604a55c
commit
a72f6acef6
@ -31,7 +31,10 @@ float safe_sqrt(float v);
|
||||
enum Rotation rotation_combination(enum Rotation r1, enum Rotation r2, bool *found = NULL);
|
||||
|
||||
// return distance in meters between two locations
|
||||
int32_t get_distance(const struct Location *loc1, const struct Location *loc2);
|
||||
float get_distance(const struct Location *loc1, const struct Location *loc2);
|
||||
|
||||
// return distance in centimeters between two locations
|
||||
int32_t get_distance_cm(const struct Location *loc1, const struct Location *loc2);
|
||||
|
||||
// return bearing in centi-degrees between two locations
|
||||
int32_t get_bearing(const struct Location *loc1, const struct Location *loc2);
|
||||
|
@ -42,7 +42,7 @@ static float longitude_scale(const struct Location *loc)
|
||||
|
||||
// return distance in meters to between two locations, or -1
|
||||
// if one of the locations is invalid
|
||||
int32_t get_distance(const struct Location *loc1, const struct Location *loc2)
|
||||
float get_distance(const struct Location *loc1, const struct Location *loc2)
|
||||
{
|
||||
if (loc1->lat == 0 || loc1->lng == 0)
|
||||
return -1;
|
||||
@ -53,6 +53,13 @@ int32_t get_distance(const struct Location *loc1, const struct Location *loc2)
|
||||
return sqrt(sq(dlat) + sq(dlong)) * .01113195;
|
||||
}
|
||||
|
||||
// return distance in centimeters to between two locations, or -1 if
|
||||
// one of the locations is invalid
|
||||
int32_t get_distance_cm(const struct Location *loc1, const struct Location *loc2)
|
||||
{
|
||||
return get_distance(loc1, loc2) * 100;
|
||||
}
|
||||
|
||||
// return bearing in centi-degrees between two locations
|
||||
int32_t get_bearing(const struct Location *loc1, const struct Location *loc2)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user