AP_Common: Add a radian method for getting location bearings

This commit is contained in:
Michael du Breuil 2019-10-16 23:28:53 -07:00 committed by Randy Mackay
parent 82a7116142
commit a99f67fd5b
1 changed files with 2 additions and 0 deletions

View File

@ -86,6 +86,8 @@ public:
// return bearing in centi-degrees from location to loc2
int32_t get_bearing_to(const struct Location &loc2) const;
// return the bearing in radians
float get_bearing(const struct Location &loc2) const { return radians(get_bearing_to(loc2) * 0.01f); } ;
// check if lat and lng match. Ignore altitude and options
bool same_latlon_as(const Location &loc2) const;