AP_Math: Location get_bearing & get_horizontal_distance use Vector2f
This commit is contained in:
parent
d5769f70ac
commit
2a15cf86ad
@ -24,13 +24,13 @@
|
||||
#include "location.h"
|
||||
|
||||
// return horizontal distance between two positions in cm
|
||||
float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
|
||||
float get_horizontal_distance_cm(const Vector2f &origin, const Vector2f &destination)
|
||||
{
|
||||
return norm(destination.x-origin.x,destination.y-origin.y);
|
||||
return (destination - origin).length();
|
||||
}
|
||||
|
||||
// return bearing in centi-degrees between two positions
|
||||
float get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
|
||||
float get_bearing_cd(const Vector2f &origin, const Vector2f &destination)
|
||||
{
|
||||
float bearing = atan2f(destination.y-origin.y, destination.x-origin.x) * DEGX100;
|
||||
if (bearing < 0) {
|
||||
|
@ -10,10 +10,10 @@
|
||||
*/
|
||||
|
||||
// return horizontal distance in centimeters between two positions
|
||||
float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination);
|
||||
float get_horizontal_distance_cm(const Vector2f &origin, const Vector2f &destination);
|
||||
|
||||
// return bearing in centi-degrees between two positions
|
||||
float get_bearing_cd(const Vector3f &origin, const Vector3f &destination);
|
||||
float get_bearing_cd(const Vector2f &origin, const Vector2f &destination);
|
||||
|
||||
// Converts from WGS84 geodetic coordinates (lat, lon, height)
|
||||
// into WGS84 Earth Centered, Earth Fixed (ECEF) coordinates
|
||||
|
Loading…
Reference in New Issue
Block a user