AP_Math: longitude_scale function made public

Added LATLON_TO_M and LATLON_TO_CM #defines
This commit is contained in:
Randy Mackay 2013-01-27 23:21:39 +09:00
parent 4fd7630ec9
commit 7729ec950e
2 changed files with 10 additions and 1 deletions

View File

@ -30,6 +30,11 @@
#define ROTATION_COMBINATION_SUPPORT 0
// convert a longitude or latitude point to meters or centimeteres.
// Note: this does not include the longitude scaling which is dependent upon location
#define LATLON_TO_M 0.01113195f
#define LATLON_TO_CM 1.113195f
// define AP_Param types AP_Vector3f and Ap_Matrix3f
AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F);
AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F);
@ -47,6 +52,10 @@ float safe_sqrt(float v);
enum Rotation rotation_combination(enum Rotation r1, enum Rotation r2, bool *found = NULL);
#endif
// longitude_scale - returns the scaler to compensate for shrinking longitude as you move north or south from the equator
// Note: this does not include the scaling to convert longitude/latitude points to meters or centimeters
float longitude_scale(const struct Location *loc);
// return distance in meters between two locations
float get_distance(const struct Location *loc1, const struct Location *loc2);

View File

@ -26,7 +26,7 @@
// radius of earth in meters
#define RADIUS_OF_EARTH 6378100
static float longitude_scale(const struct Location *loc)
float longitude_scale(const struct Location *loc)
{
static int32_t last_lat;
static float scale = 1.0;