mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_Common: Add a radian method for getting location bearings
This commit is contained in:
parent
82a7116142
commit
a99f67fd5b
@ -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…
Reference in New Issue
Block a user