From a99f67fd5ba50f8eed833ef017a1571bd80bb3e6 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 16 Oct 2019 23:28:53 -0700 Subject: [PATCH] AP_Common: Add a radian method for getting location bearings --- libraries/AP_Common/Location.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 6ee6c4b45d..24214c4820 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -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;