AP_DDS: pre-arm check service
[ardupilot.git] / ArduCopter / defines.h
blobacba81d9539601f5a7124128df1766c66dd2eb67
1 #pragma once
3 #include <AP_HAL/AP_HAL_Boards.h>
5 // Frame types
6 #define UNDEFINED_FRAME 0
7 #define MULTICOPTER_FRAME 1
8 #define HELI_FRAME 2
10 // Tuning enumeration
11 enum tuning_func {
12 TUNING_NONE = 0, //
13 TUNING_STABILIZE_ROLL_PITCH_KP = 1, // stabilize roll/pitch angle controller's P term
14 TUNING_STABILIZE_YAW_KP = 3, // stabilize yaw heading controller's P term
15 TUNING_RATE_ROLL_PITCH_KP = 4, // body frame roll/pitch rate controller's P term
16 TUNING_RATE_ROLL_PITCH_KI = 5, // body frame roll/pitch rate controller's I term
17 TUNING_YAW_RATE_KP = 6, // body frame yaw rate controller's P term
18 TUNING_THROTTLE_RATE_KP = 7, // throttle rate controller's P term (desired rate to acceleration or motor output)
19 TUNING_WP_SPEED = 10, // maximum speed to next way point (0 to 10m/s)
20 TUNING_LOITER_POSITION_KP = 12, // loiter distance controller's P term (position error to speed)
21 TUNING_HELI_EXTERNAL_GYRO = 13, // TradHeli specific external tail gyro gain
22 TUNING_ALTITUDE_HOLD_KP = 14, // altitude hold controller's P term (alt error to desired rate)
23 TUNING_RATE_ROLL_PITCH_KD = 21, // body frame roll/pitch rate controller's D term
24 TUNING_VEL_XY_KP = 22, // loiter rate controller's P term (speed error to tilt angle)
25 TUNING_ACRO_RP_RATE = 25, // acro controller's desired roll and pitch rate in deg/s
26 TUNING_YAW_RATE_KD = 26, // body frame yaw rate controller's D term
27 TUNING_VEL_XY_KI = 28, // loiter rate controller's I term (speed error to tilt angle)
28 TUNING_AHRS_YAW_KP = 30, // ahrs's compass effect on yaw angle (0 = very low, 1 = very high)
29 TUNING_AHRS_KP = 31, // accelerometer effect on roll/pitch angle (0=low)
30 TUNING_ACCEL_Z_KP = 34, // accel based throttle controller's P term
31 TUNING_ACCEL_Z_KI = 35, // accel based throttle controller's I term
32 TUNING_ACCEL_Z_KD = 36, // accel based throttle controller's D term
33 TUNING_DECLINATION = 38, // compass declination in radians
34 TUNING_CIRCLE_RATE = 39, // circle turn rate in degrees (hard coded to about 45 degrees in either direction)
35 TUNING_ACRO_YAW_RATE = 40, // acro controller's desired yaw rate in deg/s
36 TUNING_RANGEFINDER_GAIN = 41, // unused
37 TUNING_EKF_VERTICAL_POS = 42, // unused
38 TUNING_EKF_HORIZONTAL_POS = 43, // unused
39 TUNING_EKF_ACCEL_NOISE = 44, // unused
40 TUNING_RC_FEEL_RP = 45, // roll-pitch input smoothing
41 TUNING_RATE_PITCH_KP = 46, // body frame pitch rate controller's P term
42 TUNING_RATE_PITCH_KI = 47, // body frame pitch rate controller's I term
43 TUNING_RATE_PITCH_KD = 48, // body frame pitch rate controller's D term
44 TUNING_RATE_ROLL_KP = 49, // body frame roll rate controller's P term
45 TUNING_RATE_ROLL_KI = 50, // body frame roll rate controller's I term
46 TUNING_RATE_ROLL_KD = 51, // body frame roll rate controller's D term
47 TUNING_RATE_PITCH_FF = 52, // body frame pitch rate controller FF term
48 TUNING_RATE_ROLL_FF = 53, // body frame roll rate controller FF term
49 TUNING_RATE_YAW_FF = 54, // body frame yaw rate controller FF term
50 TUNING_RATE_MOT_YAW_HEADROOM = 55, // motors yaw headroom minimum
51 TUNING_RATE_YAW_FILT = 56, // yaw rate input filter
52 UNUSED = 57, // was winch control
53 TUNING_SYSTEM_ID_MAGNITUDE = 58, // magnitude of the system ID signal
54 TUNING_POS_CONTROL_ANGLE_MAX = 59 // position controller maximum angle
57 // Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter
58 #define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)
59 #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl
60 #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
61 #define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters)
64 // Airmode
65 enum class AirMode {
66 AIRMODE_NONE,
67 AIRMODE_DISABLED,
68 AIRMODE_ENABLED,
71 // bit options for DEV_OPTIONS parameter
72 enum DevOptions {
73 DevOptionADSBMAVLink = 1,
74 DevOptionVFR_HUDRelativeAlt = 2,
77 // Logging parameters - only 32 messages are available to the vehicle here.
78 enum LoggingParameters {
79 LOG_CONTROL_TUNING_MSG,
80 LOG_DATA_INT16_MSG,
81 LOG_DATA_UINT16_MSG,
82 LOG_DATA_INT32_MSG,
83 LOG_DATA_UINT32_MSG,
84 LOG_DATA_FLOAT_MSG,
85 LOG_PARAMTUNE_MSG,
86 LOG_HELI_MSG,
87 LOG_GUIDED_POSITION_TARGET_MSG,
88 LOG_SYSIDD_MSG,
89 LOG_SYSIDS_MSG,
90 LOG_GUIDED_ATTITUDE_TARGET_MSG
93 #define MASK_LOG_ATTITUDE_FAST (1<<0)
94 #define MASK_LOG_ATTITUDE_MED (1<<1)
95 #define MASK_LOG_GPS (1<<2)
96 #define MASK_LOG_PM (1<<3)
97 #define MASK_LOG_CTUN (1<<4)
98 #define MASK_LOG_NTUN (1<<5)
99 #define MASK_LOG_RCIN (1<<6)
100 #define MASK_LOG_IMU (1<<7)
101 #define MASK_LOG_CMD (1<<8)
102 #define MASK_LOG_CURRENT (1<<9)
103 #define MASK_LOG_RCOUT (1<<10)
104 #define MASK_LOG_OPTFLOW (1<<11)
105 #define MASK_LOG_PID (1<<12)
106 #define MASK_LOG_COMPASS (1<<13)
107 #define MASK_LOG_INAV (1<<14) // deprecated
108 #define MASK_LOG_CAMERA (1<<15)
109 #define MASK_LOG_MOTBATT (1UL<<17)
110 #define MASK_LOG_IMU_FAST (1UL<<18)
111 #define MASK_LOG_IMU_RAW (1UL<<19)
112 #define MASK_LOG_VIDEO_STABILISATION (1UL<<20)
113 #define MASK_LOG_FTN_FAST (1UL<<21)
114 #define MASK_LOG_ANY 0xFFFF
116 // Radio failsafe definitions (FS_THR parameter)
117 #define FS_THR_DISABLED 0
118 #define FS_THR_ENABLED_ALWAYS_RTL 1
119 #define FS_THR_ENABLED_CONTINUE_MISSION 2 // Removed in 4.0+, now use fs_options
120 #define FS_THR_ENABLED_ALWAYS_LAND 3
121 #define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL 4
122 #define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND 5
123 #define FS_THR_ENABLED_AUTO_RTL_OR_RTL 6
124 #define FS_THR_ENABLED_BRAKE_OR_LAND 7
126 // GCS failsafe definitions (FS_GCS_ENABLE parameter)
127 #define FS_GCS_DISABLED 0
128 #define FS_GCS_ENABLED_ALWAYS_RTL 1
129 #define FS_GCS_ENABLED_CONTINUE_MISSION 2 // Removed in 4.0+, now use fs_options
130 #define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL 3
131 #define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND 4
132 #define FS_GCS_ENABLED_ALWAYS_LAND 5
133 #define FS_GCS_ENABLED_AUTO_RTL_OR_RTL 6
134 #define FS_GCS_ENABLED_BRAKE_OR_LAND 7
136 // EKF failsafe definitions (FS_EKF_ACTION parameter)
137 #define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe
138 #define FS_EKF_ACTION_ALTHOLD 2 // switch to ALTHOLD mode on EKF failsafe
139 #define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3 // switch to Land mode on EKF failsafe even if in a manual flight mode like stabilize
141 // for PILOT_THR_BHV parameter
142 #define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0)
143 #define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1)
144 #define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2)