Browse Source

AP_Common: Add a radian method for getting location bearings

master
Michael du Breuil 5 years ago committed by Randy Mackay
parent
commit
a99f67fd5b
  1. 2
      libraries/AP_Common/Location.h

2
libraries/AP_Common/Location.h

@ -86,6 +86,8 @@ public:
// return bearing in centi-degrees from location to loc2 // return bearing in centi-degrees from location to loc2
int32_t get_bearing_to(const struct Location &loc2) const; 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 // check if lat and lng match. Ignore altitude and options
bool same_latlon_as(const Location &loc2) const; bool same_latlon_as(const Location &loc2) const;

Loading…
Cancel
Save