defines.h 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220
  1. #pragma once
  2. #include <AP_HAL/AP_HAL_Boards.h>
  3. // Just so that it's completely clear...
  4. #define ENABLED 1
  5. #define DISABLED 0
  6. // this avoids a very common config error
  7. #define ENABLE ENABLED
  8. #define DISABLE DISABLED
  9. #define BOTTOM_DETECTOR_TRIGGER_SEC 1.0
  10. #define SURFACE_DETECTOR_TRIGGER_SEC 1.0
  11. enum AutoSurfaceState {
  12. AUTO_SURFACE_STATE_GO_TO_LOCATION,
  13. AUTO_SURFACE_STATE_ASCEND
  14. };
  15. // Autopilot Yaw Mode enumeration
  16. enum autopilot_yaw_mode {
  17. AUTO_YAW_HOLD = 0, // pilot controls the heading
  18. AUTO_YAW_LOOK_AT_NEXT_WP = 1, // point towards next waypoint (no pilot input accepted)
  19. AUTO_YAW_ROI = 2, // point towards a location held in roi_WP (no pilot input accepted)
  20. AUTO_YAW_LOOK_AT_HEADING = 3, // point towards a particular angle (not pilot input accepted)
  21. AUTO_YAW_LOOK_AHEAD = 4, // point in the direction the vehicle is moving
  22. AUTO_YAW_RESETTOARMEDYAW = 5, // point towards heading at time motors were armed
  23. AUTO_YAW_CORRECT_XTRACK = 6 // steer the sub in order to correct for crosstrack error during line following
  24. };
  25. // Auto Pilot Modes enumeration
  26. enum control_mode_t {
  27. STABILIZE = 0, // manual angle with manual depth/throttle
  28. ACRO = 1, // manual body-frame angular rate with manual depth/throttle
  29. ALT_HOLD = 2, // manual angle with automatic depth/throttle
  30. AUTO = 3, // fully automatic waypoint control using mission commands
  31. GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
  32. CIRCLE = 7, // automatic circular flight with automatic throttle
  33. SURFACE = 9, // automatically return to surface, pilot maintains horizontal control
  34. POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
  35. MANUAL = 19, // Pass-through input with no stabilization
  36. MOTOR_DETECT = 20, // Automatically detect motors orientation
  37. CLEAN = 21, //self define to control track
  38. SPORT = 22
  39. };
  40. enum mode_reason_t {
  41. MODE_REASON_UNKNOWN=0,
  42. MODE_REASON_TX_COMMAND,
  43. MODE_REASON_GCS_COMMAND,
  44. MODE_REASON_RADIO_FAILSAFE,
  45. MODE_REASON_BATTERY_FAILSAFE,
  46. MODE_REASON_GCS_FAILSAFE,
  47. MODE_REASON_EKF_FAILSAFE,
  48. MODE_REASON_GPS_GLITCH,
  49. MODE_REASON_MISSION_END,
  50. MODE_REASON_THROTTLE_SURFACE_ESCAPE,
  51. MODE_REASON_FENCE_BREACH,
  52. MODE_REASON_TERRAIN_FAILSAFE,
  53. MODE_REASON_SURFACE_COMPLETE,
  54. MODE_REASON_LEAK_FAILSAFE,
  55. MODE_REASON_BAD_DEPTH
  56. };
  57. // Acro Trainer types
  58. #define ACRO_TRAINER_DISABLED 0
  59. #define ACRO_TRAINER_LEVELING 1
  60. #define ACRO_TRAINER_LIMITED 2
  61. // Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter
  62. #define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)
  63. #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl
  64. #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last
  65. #define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicotpers)
  66. #define WP_YAW_BEHAVIOR_CORRECT_XTRACK 4 // point towards intermediate position target during line following
  67. // Auto modes
  68. enum AutoMode {
  69. Auto_WP,
  70. Auto_CircleMoveToEdge,
  71. Auto_Circle,
  72. Auto_Spline,
  73. Auto_NavGuided,
  74. Auto_Loiter,
  75. Auto_TerrainRecover
  76. };
  77. // Guided modes
  78. enum GuidedMode {
  79. Guided_WP,
  80. Guided_Velocity,
  81. Guided_PosVel,
  82. Guided_Angle,
  83. };
  84. // RTL states
  85. enum RTLState {
  86. RTL_InitialClimb,
  87. RTL_ReturnHome,
  88. RTL_LoiterAtHome,
  89. RTL_FinalDescent,
  90. RTL_Land
  91. };
  92. // Logging parameters
  93. enum LoggingParameters {
  94. TYPE_AIRSTART_MSG,
  95. TYPE_GROUNDSTART_MSG,
  96. LOG_CONTROL_TUNING_MSG,
  97. LOG_DATA_INT16_MSG,
  98. LOG_DATA_UINT16_MSG,
  99. LOG_DATA_INT32_MSG,
  100. LOG_DATA_UINT32_MSG,
  101. LOG_DATA_FLOAT_MSG,
  102. LOG_MOTBATT_MSG,
  103. LOG_PARAMTUNE_MSG,
  104. LOG_GUIDEDTARGET_MSG
  105. };
  106. #define MASK_LOG_ATTITUDE_FAST (1<<0)
  107. #define MASK_LOG_ATTITUDE_MED (1<<1)
  108. #define MASK_LOG_GPS (1<<2)
  109. #define MASK_LOG_PM (1<<3)
  110. #define MASK_LOG_CTUN (1<<4)
  111. #define MASK_LOG_NTUN (1<<5)
  112. #define MASK_LOG_RCIN (1<<6)
  113. #define MASK_LOG_IMU (1<<7)
  114. #define MASK_LOG_CMD (1<<8)
  115. #define MASK_LOG_CURRENT (1<<9)
  116. #define MASK_LOG_RCOUT (1<<10)
  117. #define MASK_LOG_OPTFLOW (1<<11)
  118. #define MASK_LOG_PID (1<<12)
  119. #define MASK_LOG_COMPASS (1<<13)
  120. #define MASK_LOG_CAMERA (1<<15)
  121. #define MASK_LOG_MOTBATT (1UL<<17)
  122. #define MASK_LOG_IMU_FAST (1UL<<18)
  123. #define MASK_LOG_IMU_RAW (1UL<<19)
  124. #define MASK_LOG_ANY 0xFFFF
  125. // GCS failsafe
  126. #ifndef FS_GCS
  127. # define FS_GCS DISABLED
  128. #endif
  129. #ifndef FS_GCS_TIMEOUT_MS
  130. # define FS_GCS_TIMEOUT_MS 2500 // gcs failsafe triggers after this number of milliseconds with no GCS heartbeat
  131. #endif
  132. // missing terrain data failsafe
  133. #ifndef FS_TERRAIN_TIMEOUT_MS
  134. #define FS_TERRAIN_TIMEOUT_MS 1000 // 1 second of unhealthy rangefinder and/or missing terrain data will trigger failsafe
  135. #endif
  136. //////////////////////////////////////////////////////////////////////////////
  137. // EKF Failsafe
  138. // EKF failsafe definitions (FS_EKF_ENABLE parameter)
  139. #define FS_EKF_ACTION_DISABLED 0 // Disabled
  140. #define FS_EKF_ACTION_WARN_ONLY 1 // Send warning to gcs
  141. #define FS_EKF_ACTION_DISARM 2 // Disarm
  142. #ifndef FS_EKF_ACTION_DEFAULT
  143. # define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_DISABLED // EKF failsafe
  144. #endif
  145. #ifndef FS_EKF_THRESHOLD_DEFAULT
  146. # define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered
  147. #endif
  148. // GCS failsafe definitions (FS_GCS_ENABLE parameter)
  149. #define FS_GCS_DISABLED 0 // Disabled
  150. #define FS_GCS_WARN_ONLY 1 // Only send warning to gcs (only useful with multiple gcs links)
  151. #define FS_GCS_DISARM 2 // Disarm
  152. #define FS_GCS_HOLD 3 // Switch depth hold mode or poshold mode if available
  153. #define FS_GCS_SURFACE 4 // Switch to surface mode
  154. // Leak failsafe definitions (FS_LEAK_ENABLE parameter)
  155. #define FS_LEAK_DISABLED 0 // Disabled
  156. #define FS_LEAK_WARN_ONLY 1 // Only send warning to gcs
  157. #define FS_LEAK_SURFACE 2 // Switch to surface mode
  158. // Internal pressure failsafe threshold (FS_PRESS_MAX parameter)
  159. #define FS_PRESS_MAX_DEFAULT 105000 // Maximum internal pressure in pascal before failsafe is triggered
  160. // Internal pressure failsafe definitions (FS_PRESS_ENABLE parameter)
  161. #define FS_PRESS_DISABLED 0
  162. #define FS_PRESS_WARN_ONLY 1
  163. // Internal temperature failsafe threshold (FS_TEMP_MAX parameter)
  164. #define FS_TEMP_MAX_DEFAULT 62 // Maximum internal pressure in degrees C before failsafe is triggered
  165. // Internal temperature failsafe definitions (FS_TEMP_ENABLE parameter)
  166. #define FS_TEMP_DISABLED 0
  167. #define FS_TEMP_WARN_ONLY 1
  168. // Crash failsafe options
  169. #define FS_CRASH_DISABLED 0
  170. #define FS_CRASH_WARN_ONLY 1
  171. #define FS_CRASH_DISARM 2
  172. // Terrain failsafe actions for AUTO mode
  173. #define FS_TERRAIN_DISARM 0
  174. #define FS_TERRAIN_HOLD 1
  175. #define FS_TERRAIN_SURFACE 2
  176. // Pilot input failsafe actions
  177. #define FS_PILOT_INPUT_DISABLED 0
  178. #define FS_PILOT_INPUT_WARN_ONLY 1
  179. #define FS_PILOT_INPUT_DISARM 2
  180. // Amount of time to attempt recovery of valid rangefinder data before
  181. // initiating terrain failsafe action
  182. #define FS_TERRAIN_RECOVER_TIMEOUT_MS 10000
  183. // for mavlink SET_POSITION_TARGET messages
  184. #define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2))
  185. #define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4) | (1<<5))
  186. #define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7) | (1<<8))
  187. #define MAVLINK_SET_POS_TYPE_MASK_FORCE (1<<9)
  188. #define MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE (1<<10)
  189. #define MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE (1<<11)