AP_Module_Structures.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164
  1. /*
  2. this defines data structures for public module interfaces in
  3. ArduPilot.
  4. These structures are designed to not depend on other headers inside
  5. ArduPilot, although they do depend on the general ABI of the
  6. platform, and thus can depend on compilation options to some extent
  7. */
  8. #ifdef __cplusplus
  9. extern "C" {
  10. #endif
  11. #include <stdint.h>
  12. #include <stdbool.h>
  13. #define AHRS_state_version 3
  14. #define gyro_sample_version 1
  15. #define accel_sample_version 2
  16. enum AHRS_status {
  17. AHRS_STATUS_INITIALISING = 0,
  18. AHRS_STATUS_UNHEALTHY = 1,
  19. AHRS_STATUS_HEALTHY = 2
  20. };
  21. /*
  22. export the attitude and position of the vehicle.
  23. */
  24. struct AHRS_state {
  25. // version of this structure (AHRS_state_version)
  26. uint32_t structure_version;
  27. // time since boot in microseconds
  28. uint64_t time_us;
  29. // status of AHRS solution
  30. enum AHRS_status status;
  31. // quaternion attitude, first element is length scalar. Same
  32. // conventions as AP_Math/quaternion.h
  33. float quat[4];
  34. // euler angles in radians. Order is roll, pitch, yaw
  35. float eulers[3];
  36. // global origin
  37. struct {
  38. // true when origin has been initialised with a global position
  39. bool initialised;
  40. // latitude and longitude in degrees * 10^7 (approx 1cm resolution)
  41. int32_t latitude;
  42. int32_t longitude;
  43. // altitude AMSL in meters, positive up
  44. float altitude;
  45. } origin;
  46. // global position
  47. struct {
  48. // true when we have a global position
  49. bool available;
  50. // latitude and longitude in degrees * 10^7 (approx 1cm resolution)
  51. int32_t latitude;
  52. int32_t longitude;
  53. // altitude AMSL in meters, positive up
  54. float altitude;
  55. } position;
  56. // NED relative position in meters. Relative to origin
  57. float relative_position[3];
  58. // current rotational rates in radians/second in body frame
  59. // order is roll, pitch, yaw
  60. float gyro_rate[3];
  61. // current earth frame acceleration estimate, including
  62. // gravitational forces, m/s/s order is NED
  63. float accel_ef[3];
  64. // the current primary accel instance
  65. uint8_t primary_accel;
  66. // the current primary gyro instance
  67. uint8_t primary_gyro;
  68. // current gyro bias. This is relative to the gyro data in
  69. // gyro_sample for primary_gyro. It should be added to a gyro
  70. // sample to get the corrected gyro estimate
  71. float gyro_bias[3];
  72. // north-east-down velocity m/s
  73. float velocity_ned[3];
  74. };
  75. /*
  76. export corrected gyro samples at hardware sampling rate
  77. */
  78. struct gyro_sample {
  79. // version of this structure (gyro_sample_version)
  80. uint32_t structure_version;
  81. // which gyro this is
  82. uint8_t instance;
  83. // time since boot in microseconds
  84. uint64_t time_us;
  85. // time associated with this sample (seconds)
  86. float delta_time;
  87. // body frame rates in radian/sec
  88. float gyro[3];
  89. };
  90. /*
  91. export corrected accel samples at hardware sampling rate
  92. */
  93. struct accel_sample {
  94. // version of this structure (accel_sample_version)
  95. uint32_t structure_version;
  96. // which accel this is
  97. uint8_t instance;
  98. // time since boot in microseconds
  99. uint64_t time_us;
  100. // time associated with this sample (seconds)
  101. float delta_time;
  102. // body frame rates in m/s/s
  103. float accel[3];
  104. // true if external frame sync is set
  105. bool fsync_set;
  106. };
  107. /*
  108. prototypes for hook functions
  109. */
  110. typedef void (*ap_hook_setup_start_fn_t)(uint64_t);
  111. void ap_hook_setup_start(uint64_t time_us);
  112. typedef void (*ap_hook_setup_complete_fn_t)(uint64_t);
  113. void ap_hook_setup_complete(uint64_t time_us);
  114. typedef void (*ap_hook_AHRS_update_fn_t)(const struct AHRS_state *);
  115. void ap_hook_AHRS_update(const struct AHRS_state *state);
  116. typedef void (*ap_hook_gyro_sample_fn_t)(const struct gyro_sample *);
  117. void ap_hook_gyro_sample(const struct gyro_sample *state);
  118. typedef void (*ap_hook_accel_sample_fn_t)(const struct accel_sample *);
  119. void ap_hook_accel_sample(const struct accel_sample *state);
  120. #ifdef __cplusplus
  121. }
  122. #endif