mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Math: get_horizontal_cm() simplify
This commit is contained in:
parent
9e11f09a7f
commit
28d9be1cc0
@ -23,12 +23,6 @@
|
|||||||
#include "AP_Math.h"
|
#include "AP_Math.h"
|
||||||
#include "location.h"
|
#include "location.h"
|
||||||
|
|
||||||
// return horizontal distance between two positions in cm
|
|
||||||
float get_horizontal_distance_cm(const Vector2f &origin, const Vector2f &destination)
|
|
||||||
{
|
|
||||||
return (destination - origin).length();
|
|
||||||
}
|
|
||||||
|
|
||||||
// return bearing in centi-degrees between two positions
|
// return bearing in centi-degrees between two positions
|
||||||
float get_bearing_cd(const Vector2f &origin, const Vector2f &destination)
|
float get_bearing_cd(const Vector2f &origin, const Vector2f &destination)
|
||||||
{
|
{
|
||||||
|
@ -9,8 +9,12 @@
|
|||||||
* LOCATION
|
* LOCATION
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// return horizontal distance in centimeters between two positions
|
// return horizontal distance between two positions in cm
|
||||||
float get_horizontal_distance_cm(const Vector2f &origin, const Vector2f &destination);
|
template <typename T>
|
||||||
|
float get_horizontal_distance_cm(const Vector2<T> &origin, const Vector2<T> &destination)
|
||||||
|
{
|
||||||
|
return (destination - origin).length();
|
||||||
|
}
|
||||||
|
|
||||||
// return bearing in centi-degrees between two positions
|
// return bearing in centi-degrees between two positions
|
||||||
float get_bearing_cd(const Vector2f &origin, const Vector2f &destination);
|
float get_bearing_cd(const Vector2f &origin, const Vector2f &destination);
|
||||||
|
Loading…
Reference in New Issue
Block a user