definitions.h 3.1 KB

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