diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 3f94b3db03..8fc60d561c 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -10,7 +10,6 @@ #include "definitions.h" #include "edc.h" -#include "location.h" #include "matrix3.h" #include "polygon.h" #include "quaternion.h" @@ -18,6 +17,7 @@ #include "vector2.h" #include "vector3.h" #include "spline5.h" +#include "location.h" // define AP_Param types AP_Vector3f and Ap_Matrix3f AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F); diff --git a/libraries/AP_Math/location.cpp b/libraries/AP_Math/location.cpp index 591ce47d1b..4f2cae3da5 100644 --- a/libraries/AP_Math/location.cpp +++ b/libraries/AP_Math/location.cpp @@ -23,7 +23,6 @@ #include #include "AP_Math.h" #include "location.h" -#include "AP_Common/Location.h" // return horizontal distance between two positions in cm float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination) diff --git a/libraries/AP_Math/location.h b/libraries/AP_Math/location.h index 7f198cbbf1..388841b017 100644 --- a/libraries/AP_Math/location.h +++ b/libraries/AP_Math/location.h @@ -7,6 +7,7 @@ #include "vector2.h" #include "vector3.h" +#include // scaling factor from 1e-7 degrees to meters at equator // == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH