mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: remove trailing whitespaces and tabs
This commit is contained in:
parent
5148e41c1a
commit
7f685a12bd
@ -13,7 +13,7 @@
|
|||||||
#ifndef M_PI_2
|
#ifndef M_PI_2
|
||||||
#define M_PI_2 (M_PI / 2)
|
#define M_PI_2 (M_PI / 2)
|
||||||
#endif
|
#endif
|
||||||
#else // Standard single precision math
|
#else // Standard single precision math
|
||||||
#ifdef M_PI
|
#ifdef M_PI
|
||||||
#undef M_PI
|
#undef M_PI
|
||||||
#endif
|
#endif
|
||||||
@ -35,29 +35,29 @@
|
|||||||
#ifndef MATH_CHECK_INDEXES
|
#ifndef MATH_CHECK_INDEXES
|
||||||
#define MATH_CHECK_INDEXES 0
|
#define MATH_CHECK_INDEXES 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define DEG_TO_RAD (M_PI / 180.0f)
|
#define DEG_TO_RAD (M_PI / 180.0f)
|
||||||
#define RAD_TO_DEG (180.0f / M_PI)
|
#define RAD_TO_DEG (180.0f / M_PI)
|
||||||
|
|
||||||
// GPS Specific double precision conversions
|
// GPS Specific double precision conversions
|
||||||
// The precision here does matter when using the wsg* functions for converting
|
// The precision here does matter when using the wsg* functions for converting
|
||||||
// between LLH and ECEF coordinates.
|
// between LLH and ECEF coordinates.
|
||||||
#define DEG_TO_RAD_DOUBLE 0.0174532925199432954743716805978692718781530857086181640625
|
#define DEG_TO_RAD_DOUBLE 0.0174532925199432954743716805978692718781530857086181640625
|
||||||
#define RAD_TO_DEG_DOUBLE 57.29577951308232286464772187173366546630859375
|
#define RAD_TO_DEG_DOUBLE 57.29577951308232286464772187173366546630859375
|
||||||
|
|
||||||
#define RadiansToCentiDegrees(x) (static_cast<float>(x) * RAD_TO_DEG * static_cast<float>(100))
|
#define RadiansToCentiDegrees(x) (static_cast<float>(x) * RAD_TO_DEG * static_cast<float>(100))
|
||||||
|
|
||||||
// acceleration due to gravity in m/s/s
|
// acceleration due to gravity in m/s/s
|
||||||
#define GRAVITY_MSS 9.80665f
|
#define GRAVITY_MSS 9.80665f
|
||||||
|
|
||||||
// radius of earth in meters
|
// radius of earth in meters
|
||||||
#define RADIUS_OF_EARTH 6378100
|
#define RADIUS_OF_EARTH 6378100
|
||||||
|
|
||||||
// convert a longitude or latitude point to meters or centimeteres.
|
// convert a longitude or latitude point to meters or centimeteres.
|
||||||
// Note: this does not include the longitude scaling which is dependent upon location
|
// Note: this does not include the longitude scaling which is dependent upon location
|
||||||
#define LATLON_TO_M 0.01113195f
|
#define LATLON_TO_M 0.01113195f
|
||||||
#define LATLON_TO_CM 1.113195f
|
#define LATLON_TO_CM 1.113195f
|
||||||
|
|
||||||
// Semi-major axis of the Earth, in meters.
|
// Semi-major axis of the Earth, in meters.
|
||||||
#define WGS84_A 6378137.0
|
#define WGS84_A 6378137.0
|
||||||
//Inverse flattening of the Earth
|
//Inverse flattening of the Earth
|
||||||
@ -68,7 +68,7 @@
|
|||||||
#define WGS84_B (WGS84_A * (1 - WGS84_F))
|
#define WGS84_B (WGS84_A * (1 - WGS84_F))
|
||||||
// Eccentricity of the Earth
|
// Eccentricity of the Earth
|
||||||
#define WGS84_E (sqrt(2 * WGS84_F - WGS84_F * WGS84_F))
|
#define WGS84_E (sqrt(2 * WGS84_F - WGS84_F * WGS84_F))
|
||||||
|
|
||||||
#define NSEC_PER_SEC 1000000000ULL
|
#define NSEC_PER_SEC 1000000000ULL
|
||||||
#define NSEC_PER_USEC 1000ULL
|
#define NSEC_PER_USEC 1000ULL
|
||||||
#define USEC_PER_SEC 1000000ULL
|
#define USEC_PER_SEC 1000000ULL
|
||||||
|
Loading…
Reference in New Issue
Block a user