APM:Libraries
definitions.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <cmath>
4 
5 #include <AP_HAL/AP_HAL.h>
6 
7 #ifdef M_PI
8 # undef M_PI
9 #endif
10 #define M_PI (3.141592653589793f)
11 
12 #ifdef M_PI_2
13 # undef M_PI_2
14 #endif
15 #define M_PI_2 (M_PI / 2)
16 
17 #define M_GOLDEN 1.6180339f
18 
19 #define M_2PI (M_PI * 2)
20 
21 // MATH_CHECK_INDEXES modifies some objects (e.g. SoloGimbalEKF) to
22 // include more debug information. It is also used by some functions
23 // to add extra code for debugging purposes. If you wish to activate
24 // this, do it here or as part of the top-level Makefile -
25 // e.g. Tools/Replay/Makefile
26 #ifndef MATH_CHECK_INDEXES
27  #define MATH_CHECK_INDEXES 0
28 #endif
29 
30 #define DEG_TO_RAD (M_PI / 180.0f)
31 #define RAD_TO_DEG (180.0f / M_PI)
32 
33 // Centi-degrees to radians
34 #define DEGX100 5729.57795f
35 
36 // GPS Specific double precision conversions
37 // The precision here does matter when using the wsg* functions for converting
38 // between LLH and ECEF coordinates.
39 #ifdef ALLOW_DOUBLE_MATH_FUNCTIONS
40 static const double DEG_TO_RAD_DOUBLE = asin(1) / 90;
41 static const double RAD_TO_DEG_DOUBLE = 1 / DEG_TO_RAD_DOUBLE;
42 #endif
43 
44 #define RadiansToCentiDegrees(x) (static_cast<float>(x) * RAD_TO_DEG * static_cast<float>(100))
45 
46 // acceleration due to gravity in m/s/s
47 #define GRAVITY_MSS 9.80665f
48 
49 // radius of earth in meters
50 #define RADIUS_OF_EARTH 6378100
51 
52 // convert a longitude or latitude point to meters or centimeters.
53 // Note: this does not include the longitude scaling which is dependent upon location
54 #define LATLON_TO_M 0.01113195f
55 #define LATLON_TO_CM 1.113195f
56 
57 // Semi-major axis of the Earth, in meters.
58 static const double WGS84_A = 6378137.0;
59 
60 //Inverse flattening of the Earth
61 static const double WGS84_IF = 298.257223563;
62 
63 // The flattening of the Earth
64 static const double WGS84_F = ((double)1.0 / WGS84_IF);
65 
66 // Semi-minor axis of the Earth in meters
67 static const double WGS84_B = (WGS84_A * (1 - WGS84_F));
68 
69 // Eccentricity of the Earth
70 #ifdef ALLOW_DOUBLE_MATH_FUNCTIONS
71 static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F));
72 #endif
73 
74 #define C_TO_KELVIN 273.15f
75 
76 // Gas Constant is from Aerodynamics for Engineering Students, Third Edition, E.L.Houghton and N.B.Carruthers
77 #define ISA_GAS_CONSTANT 287.26f
78 #define ISA_LAPSE_RATE 0.0065f
79 
80 // Standard Sea Level values
81 // Ref: https://en.wikipedia.org/wiki/Standard_sea_level
82 #define SSL_AIR_DENSITY 1.225f // kg/m^3
83 #define SSL_AIR_PRESSURE 101325.01576f // Pascal
84 #define SSL_AIR_TEMPERATURE 288.15f // K
85 
86 /*
87  use AP_ prefix to prevent conflict with OS headers, such as NuttX
88  clock.h
89  */
90 #define AP_NSEC_PER_SEC 1000000000ULL
91 #define AP_NSEC_PER_USEC 1000ULL
92 #define AP_USEC_PER_SEC 1000000ULL
93 #define AP_USEC_PER_MSEC 1000ULL
94 #define AP_MSEC_PER_SEC 1000ULL
95 #define AP_SEC_PER_WEEK (7ULL * 86400ULL)
96 #define AP_MSEC_PER_WEEK (AP_SEC_PER_WEEK * AP_MSEC_PER_SEC)
static const double WGS84_F
Definition: definitions.h:64
static const double WGS84_B
Definition: definitions.h:67
static const double WGS84_A
Definition: definitions.h:58
static const double WGS84_IF
Definition: definitions.h:61