APM:Copter
defines.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL_Boards.h>
4 
5 // Just so that it's completely clear...
6 #define ENABLED 1
7 #define DISABLED 0
8 
9 // this avoids a very common config error
10 #define ENABLE ENABLED
11 #define DISABLE DISABLED
12 
13 // Autopilot Yaw Mode enumeration
15  AUTO_YAW_HOLD = 0, // pilot controls the heading
16  AUTO_YAW_LOOK_AT_NEXT_WP = 1, // point towards next waypoint (no pilot input accepted)
17  AUTO_YAW_ROI = 2, // point towards a location held in roi (no pilot input accepted)
18  AUTO_YAW_FIXED = 3, // point towards a particular angle (no pilot input accepted)
19  AUTO_YAW_LOOK_AHEAD = 4, // point in the direction the copter is moving
20  AUTO_YAW_RESETTOARMEDYAW = 5, // point towards heading at time motors were armed
21  AUTO_YAW_RATE = 6, // turn at a specified rate (held in auto_yaw_rate)
22 };
23 
24 // Ch6... Ch12 aux switch control
25 #define AUX_SWITCH_PWM_TRIGGER_HIGH 1800 // pwm value above which the ch7 or ch8 option will be invoked
26 #define AUX_SWITCH_PWM_TRIGGER_LOW 1200 // pwm value below which the ch7 or ch8 option will be disabled
27 
28 // values used by the ap.ch7_opt and ap.ch8_opt flags
29 #define AUX_SWITCH_LOW 0 // indicates auxiliary switch is in the low position (pwm <1200)
30 #define AUX_SWITCH_MIDDLE 1 // indicates auxiliary switch is in the middle position (pwm >1200, <1800)
31 #define AUX_SWITCH_HIGH 2 // indicates auxiliary switch is in the high position (pwm >1800)
32 
33 // Aux Switch enumeration
35  AUXSW_DO_NOTHING = 0, // aux switch disabled
36  AUXSW_FLIP = 2, // flip
37  AUXSW_SIMPLE_MODE = 3, // change to simple mode
38  AUXSW_RTL = 4, // change to RTL flight mode
39  AUXSW_SAVE_TRIM = 5, // save current position as level
40  AUXSW_SAVE_WP = 7, // save mission waypoint or RTL if in auto mode
41  AUXSW_CAMERA_TRIGGER = 9, // trigger camera servo or relay
42  AUXSW_RANGEFINDER = 10, // allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the ground
43  AUXSW_FENCE = 11, // allow enabling or disabling fence in flight
44  AUXSW_RESETTOARMEDYAW = 12, // deprecated. changes yaw to be same as when quad was armed
45  AUXSW_SUPERSIMPLE_MODE = 13, // change to simple mode in middle, super simple at top
46  AUXSW_ACRO_TRAINER = 14, // low = disabled, middle = leveled, high = leveled and limited
47  AUXSW_SPRAYER = 15, // enable/disable the crop sprayer
48  AUXSW_AUTO = 16, // change to auto flight mode
49  AUXSW_AUTOTUNE = 17, // auto tune
50  AUXSW_LAND = 18, // change to LAND flight mode
51  AUXSW_GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
52  AUXSW_PARACHUTE_ENABLE = 21, // Parachute enable/disable
53  AUXSW_PARACHUTE_RELEASE = 22, // Parachute release
54  AUXSW_PARACHUTE_3POS = 23, // Parachute disable, enable, release with 3 position switch
55  AUXSW_MISSION_RESET = 24, // Reset auto mission to start from first command
56  AUXSW_ATTCON_FEEDFWD = 25, // enable/disable the roll and pitch rate feed forward
57  AUXSW_ATTCON_ACCEL_LIM = 26, // enable/disable the roll, pitch and yaw accel limiting
58  AUXSW_RETRACT_MOUNT = 27, // Retract Mount
59  AUXSW_RELAY = 28, // Relay pin on/off (only supports first relay)
60  AUXSW_LANDING_GEAR = 29, // Landing gear controller
61  AUXSW_LOST_COPTER_SOUND = 30, // Play lost copter sound
62  AUXSW_MOTOR_ESTOP = 31, // Emergency Stop Switch
63  AUXSW_MOTOR_INTERLOCK = 32, // Motor On/Off switch
64  AUXSW_BRAKE = 33, // Brake flight mode
65  AUXSW_RELAY2 = 34, // Relay2 pin on/off (in Mission planner set CH8_OPT = 34)
66  AUXSW_RELAY3 = 35, // Relay3 pin on/off (in Mission planner set CH9_OPT = 35)
67  AUXSW_RELAY4 = 36, // Relay4 pin on/off (in Mission planner set CH10_OPT = 36)
68  AUXSW_THROW = 37, // change to THROW flight mode
69  AUXSW_AVOID_ADSB = 38, // enable AP_Avoidance library
70  AUXSW_PRECISION_LOITER = 39, // enable precision loiter
71  AUXSW_AVOID_PROXIMITY = 40, // enable object avoidance using proximity sensors (ie. horizontal lidar)
72  AUXSW_ARMDISARM = 41, // arm or disarm vehicle
73  AUXSW_SMART_RTL = 42, // change to SmartRTL flight mode
74  AUXSW_INVERTED = 43, // enable inverted flight
75  AUXSW_WINCH_ENABLE = 44, // winch enable/disable
76  AUXSW_WINCH_CONTROL = 45, // winch control
77  AUXSW_RC_OVERRIDE_ENABLE = 46, // enable RC Override
79 };
80 
81 // Frame types
82 #define UNDEFINED_FRAME 0
83 #define MULTICOPTER_FRAME 1
84 #define HELI_FRAME 2
85 
86 // HIL enumerations
87 #define HIL_MODE_DISABLED 0
88 #define HIL_MODE_SENSORS 1
89 
90 // Auto Pilot Modes enumeration
92  STABILIZE = 0, // manual airframe angle with manual throttle
93  ACRO = 1, // manual body-frame angular rate with manual throttle
94  ALT_HOLD = 2, // manual airframe angle with automatic throttle
95  AUTO = 3, // fully automatic waypoint control using mission commands
96  GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
97  LOITER = 5, // automatic horizontal acceleration with automatic throttle
98  RTL = 6, // automatic return to launching point
99  CIRCLE = 7, // automatic circular flight with automatic throttle
100  LAND = 9, // automatic landing with horizontal position control
101  DRIFT = 11, // semi-automous position, yaw and throttle control
102  SPORT = 13, // manual earth-frame angular rate control with manual throttle
103  FLIP = 14, // automatically flip the vehicle on the roll axis
104  AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
105  POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
106  BRAKE = 17, // full-brake using inertial/GPS system, no pilot input
107  THROW = 18, // throw to launch mode using inertial/GPS system, no pilot input
108  AVOID_ADSB = 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft
109  GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude
110  SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
111  FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder
112  FOLLOW = 23, // follow attempts to follow another vehicle or ground station
113 };
114 
135 };
136 
137 // Tuning enumeration
139  TUNING_NONE = 0, //
140  TUNING_STABILIZE_ROLL_PITCH_KP = 1, // stabilize roll/pitch angle controller's P term
141  TUNING_STABILIZE_YAW_KP = 3, // stabilize yaw heading controller's P term
142  TUNING_RATE_ROLL_PITCH_KP = 4, // body frame roll/pitch rate controller's P term
143  TUNING_RATE_ROLL_PITCH_KI = 5, // body frame roll/pitch rate controller's I term
144  TUNING_YAW_RATE_KP = 6, // body frame yaw rate controller's P term
145  TUNING_THROTTLE_RATE_KP = 7, // throttle rate controller's P term (desired rate to acceleration or motor output)
146  TUNING_WP_SPEED = 10, // maximum speed to next way point (0 to 10m/s)
147  TUNING_LOITER_POSITION_KP = 12, // loiter distance controller's P term (position error to speed)
148  TUNING_HELI_EXTERNAL_GYRO = 13, // TradHeli specific external tail gyro gain
149  TUNING_ALTITUDE_HOLD_KP = 14, // altitude hold controller's P term (alt error to desired rate)
150  TUNING_RATE_ROLL_PITCH_KD = 21, // body frame roll/pitch rate controller's D term
151  TUNING_VEL_XY_KP = 22, // loiter rate controller's P term (speed error to tilt angle)
152  TUNING_ACRO_RP_KP = 25, // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
153  TUNING_YAW_RATE_KD = 26, // body frame yaw rate controller's D term
154  TUNING_VEL_XY_KI = 28, // loiter rate controller's I term (speed error to tilt angle)
155  TUNING_AHRS_YAW_KP = 30, // ahrs's compass effect on yaw angle (0 = very low, 1 = very high)
156  TUNING_AHRS_KP = 31, // accelerometer effect on roll/pitch angle (0=low)
157  TUNING_ACCEL_Z_KP = 34, // accel based throttle controller's P term
158  TUNING_ACCEL_Z_KI = 35, // accel based throttle controller's I term
159  TUNING_ACCEL_Z_KD = 36, // accel based throttle controller's D term
160  TUNING_DECLINATION = 38, // compass declination in radians
161  TUNING_CIRCLE_RATE = 39, // circle turn rate in degrees (hard coded to about 45 degrees in either direction)
162  TUNING_ACRO_YAW_KP = 40, // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
163  TUNING_RANGEFINDER_GAIN = 41, // rangefinder gain
164  TUNING_EKF_VERTICAL_POS = 42, // EKF's baro vs accel (higher rely on accels more, baro impact is reduced). Range should be 0.2 ~ 4.0? 2.0 is default
165  TUNING_EKF_HORIZONTAL_POS = 43, // EKF's gps vs accel (higher rely on accels more, gps impact is reduced). Range should be 1.0 ~ 3.0? 1.5 is default
166  TUNING_EKF_ACCEL_NOISE = 44, // EKF's accel noise (lower means trust accels more, gps & baro less). Range should be 0.02 ~ 0.5 0.5 is default (but very robust at that level)
167  TUNING_RC_FEEL_RP = 45, // roll-pitch input smoothing
168  TUNING_RATE_PITCH_KP = 46, // body frame pitch rate controller's P term
169  TUNING_RATE_PITCH_KI = 47, // body frame pitch rate controller's I term
170  TUNING_RATE_PITCH_KD = 48, // body frame pitch rate controller's D term
171  TUNING_RATE_ROLL_KP = 49, // body frame roll rate controller's P term
172  TUNING_RATE_ROLL_KI = 50, // body frame roll rate controller's I term
173  TUNING_RATE_ROLL_KD = 51, // body frame roll rate controller's D term
174  TUNING_RATE_PITCH_FF = 52, // body frame pitch rate controller FF term
175  TUNING_RATE_ROLL_FF = 53, // body frame roll rate controller FF term
176  TUNING_RATE_YAW_FF = 54, // body frame yaw rate controller FF term
177  TUNING_RATE_MOT_YAW_HEADROOM = 55, // motors yaw headroom minimum
178  TUNING_RATE_YAW_FILT = 56, // yaw rate input filter
179  TUNING_WINCH = 57 // winch control (not actually a value to be tuned)
180 };
181 
182 // Acro Trainer types
183 #define ACRO_TRAINER_DISABLED 0
184 #define ACRO_TRAINER_LEVELING 1
185 #define ACRO_TRAINER_LIMITED 2
186 
187 // Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter
188 #define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)
189 #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl
190 #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
191 #define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicotpers)
192 
193 // Auto modes
194 enum AutoMode {
205 };
206 
207 // Guided modes
214 };
215 
216 // RTL states
217 enum RTLState {
223 };
224 
225 // Safe RTL states
232 };
233 
234 // Alt_Hold states
240 };
241 
242 // Loiter states
248 };
249 
250 // Sport states
256 };
257 
258 // Flip states
259 enum FlipState {
266 };
267 
271 };
272 
285 };
286 
287 // bit options for DEV_OPTIONS parameter
290 };
291 
292 // Logging parameters
312 };
313 
314 #define MASK_LOG_ATTITUDE_FAST (1<<0)
315 #define MASK_LOG_ATTITUDE_MED (1<<1)
316 #define MASK_LOG_GPS (1<<2)
317 #define MASK_LOG_PM (1<<3)
318 #define MASK_LOG_CTUN (1<<4)
319 #define MASK_LOG_NTUN (1<<5)
320 #define MASK_LOG_RCIN (1<<6)
321 #define MASK_LOG_IMU (1<<7)
322 #define MASK_LOG_CMD (1<<8)
323 #define MASK_LOG_CURRENT (1<<9)
324 #define MASK_LOG_RCOUT (1<<10)
325 #define MASK_LOG_OPTFLOW (1<<11)
326 #define MASK_LOG_PID (1<<12)
327 #define MASK_LOG_COMPASS (1<<13)
328 #define MASK_LOG_INAV (1<<14) // deprecated
329 #define MASK_LOG_CAMERA (1<<15)
330 #define MASK_LOG_MOTBATT (1UL<<17)
331 #define MASK_LOG_IMU_FAST (1UL<<18)
332 #define MASK_LOG_IMU_RAW (1UL<<19)
333 #define MASK_LOG_ANY 0xFFFF
334 
335 // DATA - event logging
336 #define DATA_AP_STATE 7
337 #define DATA_SYSTEM_TIME_SET 8
338 #define DATA_INIT_SIMPLE_BEARING 9
339 #define DATA_ARMED 10
340 #define DATA_DISARMED 11
341 #define DATA_AUTO_ARMED 15
342 #define DATA_LAND_COMPLETE_MAYBE 17
343 #define DATA_LAND_COMPLETE 18
344 #define DATA_NOT_LANDED 28
345 #define DATA_LOST_GPS 19
346 #define DATA_FLIP_START 21
347 #define DATA_FLIP_END 22
348 #define DATA_SET_HOME 25
349 #define DATA_SET_SIMPLE_ON 26
350 #define DATA_SET_SIMPLE_OFF 27
351 #define DATA_SET_SUPERSIMPLE_ON 29
352 #define DATA_AUTOTUNE_INITIALISED 30
353 #define DATA_AUTOTUNE_OFF 31
354 #define DATA_AUTOTUNE_RESTART 32
355 #define DATA_AUTOTUNE_SUCCESS 33
356 #define DATA_AUTOTUNE_FAILED 34
357 #define DATA_AUTOTUNE_REACHED_LIMIT 35
358 #define DATA_AUTOTUNE_PILOT_TESTING 36
359 #define DATA_AUTOTUNE_SAVEDGAINS 37
360 #define DATA_SAVE_TRIM 38
361 #define DATA_SAVEWP_ADD_WP 39
362 #define DATA_FENCE_ENABLE 41
363 #define DATA_FENCE_DISABLE 42
364 #define DATA_ACRO_TRAINER_DISABLED 43
365 #define DATA_ACRO_TRAINER_LEVELING 44
366 #define DATA_ACRO_TRAINER_LIMITED 45
367 #define DATA_GRIPPER_GRAB 46
368 #define DATA_GRIPPER_RELEASE 47
369 #define DATA_PARACHUTE_DISABLED 49
370 #define DATA_PARACHUTE_ENABLED 50
371 #define DATA_PARACHUTE_RELEASED 51
372 #define DATA_LANDING_GEAR_DEPLOYED 52
373 #define DATA_LANDING_GEAR_RETRACTED 53
374 #define DATA_MOTORS_EMERGENCY_STOPPED 54
375 #define DATA_MOTORS_EMERGENCY_STOP_CLEARED 55
376 #define DATA_MOTORS_INTERLOCK_DISABLED 56
377 #define DATA_MOTORS_INTERLOCK_ENABLED 57
378 #define DATA_ROTOR_RUNUP_COMPLETE 58 // Heli only
379 #define DATA_ROTOR_SPEED_BELOW_CRITICAL 59 // Heli only
380 #define DATA_EKF_ALT_RESET 60
381 #define DATA_LAND_CANCELLED_BY_PILOT 61
382 #define DATA_EKF_YAW_RESET 62
383 #define DATA_AVOIDANCE_ADSB_ENABLE 63
384 #define DATA_AVOIDANCE_ADSB_DISABLE 64
385 #define DATA_AVOIDANCE_PROXIMITY_ENABLE 65
386 #define DATA_AVOIDANCE_PROXIMITY_DISABLE 66
387 #define DATA_GPS_PRIMARY_CHANGED 67
388 #define DATA_WINCH_RELAXED 68
389 #define DATA_WINCH_LENGTH_CONTROL 69
390 #define DATA_WINCH_RATE_CONTROL 70
391 
392 // Error message sub systems and error codes
393 #define ERROR_SUBSYSTEM_MAIN 1
394 #define ERROR_SUBSYSTEM_RADIO 2
395 #define ERROR_SUBSYSTEM_COMPASS 3
396 #define ERROR_SUBSYSTEM_OPTFLOW 4
397 #define ERROR_SUBSYSTEM_FAILSAFE_RADIO 5
398 #define ERROR_SUBSYSTEM_FAILSAFE_BATT 6
399 #define ERROR_SUBSYSTEM_FAILSAFE_GPS 7 // not used
400 #define ERROR_SUBSYSTEM_FAILSAFE_GCS 8
401 #define ERROR_SUBSYSTEM_FAILSAFE_FENCE 9
402 #define ERROR_SUBSYSTEM_FLIGHT_MODE 10
403 #define ERROR_SUBSYSTEM_GPS 11
404 #define ERROR_SUBSYSTEM_CRASH_CHECK 12
405 #define ERROR_SUBSYSTEM_FLIP 13
406 #define ERROR_SUBSYSTEM_AUTOTUNE 14
407 #define ERROR_SUBSYSTEM_PARACHUTE 15
408 #define ERROR_SUBSYSTEM_EKFCHECK 16
409 #define ERROR_SUBSYSTEM_FAILSAFE_EKFINAV 17
410 #define ERROR_SUBSYSTEM_BARO 18
411 #define ERROR_SUBSYSTEM_CPU 19
412 #define ERROR_SUBSYSTEM_FAILSAFE_ADSB 20
413 #define ERROR_SUBSYSTEM_TERRAIN 21
414 #define ERROR_SUBSYSTEM_NAVIGATION 22
415 #define ERROR_SUBSYSTEM_FAILSAFE_TERRAIN 23
416 #define ERROR_SUBSYSTEM_EKF_PRIMARY 24
417 // general error codes
418 #define ERROR_CODE_ERROR_RESOLVED 0
419 #define ERROR_CODE_FAILED_TO_INITIALISE 1
420 #define ERROR_CODE_UNHEALTHY 4
421 // subsystem specific error codes -- radio
422 #define ERROR_CODE_RADIO_LATE_FRAME 2
423 // subsystem specific error codes -- failsafe_thr, batt, gps
424 #define ERROR_CODE_FAILSAFE_RESOLVED 0
425 #define ERROR_CODE_FAILSAFE_OCCURRED 1
426 // subsystem specific error codes -- compass
427 #define ERROR_CODE_COMPASS_FAILED_TO_READ 2
428 // subsystem specific error codes -- main
429 #define ERROR_CODE_MAIN_INS_DELAY 1
430 // subsystem specific error codes -- crash checker
431 #define ERROR_CODE_CRASH_CHECK_CRASH 1
432 #define ERROR_CODE_CRASH_CHECK_LOSS_OF_CONTROL 2
433 // subsystem specific error codes -- flip
434 #define ERROR_CODE_FLIP_ABANDONED 2
435 // subsystem specific error codes -- terrain
436 #define ERROR_CODE_MISSING_TERRAIN_DATA 2
437 // subsystem specific error codes -- navigation
438 #define ERROR_CODE_FAILED_TO_SET_DESTINATION 2
439 #define ERROR_CODE_RESTARTED_RTL 3
440 #define ERROR_CODE_FAILED_CIRCLE_INIT 4
441 #define ERROR_CODE_DEST_OUTSIDE_FENCE 5
442 
443 // parachute failed to deploy because of low altitude or landed
444 #define ERROR_CODE_PARACHUTE_TOO_LOW 2
445 #define ERROR_CODE_PARACHUTE_LANDED 3
446 // EKF check definitions
447 #define ERROR_CODE_EKFCHECK_BAD_VARIANCE 2
448 #define ERROR_CODE_EKFCHECK_VARIANCE_CLEARED 0
449 // Baro specific error codes
450 #define ERROR_CODE_BARO_GLITCH 2
451 // GPS specific error coces
452 #define ERROR_CODE_GPS_GLITCH 2
453 
454 // Radio failsafe definitions (FS_THR parameter)
455 #define FS_THR_DISABLED 0
456 #define FS_THR_ENABLED_ALWAYS_RTL 1
457 #define FS_THR_ENABLED_CONTINUE_MISSION 2
458 #define FS_THR_ENABLED_ALWAYS_LAND 3
459 #define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL 4
460 #define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND 5
461 
462 // GCS failsafe definitions (FS_GCS_ENABLE parameter)
463 #define FS_GCS_DISABLED 0
464 #define FS_GCS_ENABLED_ALWAYS_RTL 1
465 #define FS_GCS_ENABLED_CONTINUE_MISSION 2
466 #define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL 3
467 #define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND 4
468 
469 // EKF failsafe definitions (FS_EKF_ACTION parameter)
470 #define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe
471 #define FS_EKF_ACTION_ALTHOLD 2 // switch to ALTHOLD mode on EKF failsafe
472 #define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3 // switch to Land mode on EKF failsafe even if in a manual flight mode like stabilize
473 
474 // for mavlink SET_POSITION_TARGET messages
475 #define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2))
476 #define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4) | (1<<5))
477 #define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7) | (1<<8))
478 #define MAVLINK_SET_POS_TYPE_MASK_FORCE (1<<9)
479 #define MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE (1<<10)
480 #define MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE (1<<11)
481 
482 // for PILOT_THR_BHV parameter
483 #define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0)
484 #define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1)
485 #define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2)
control_mode_t
Definition: defines.h:91
LoggingParameters
Definition: defines.h:293
LoiterModeState
Definition: defines.h:243
RTLState
Definition: defines.h:217
LandStateType
Definition: defines.h:268
Definition: defines.h:95
Definition: defines.h:106
Definition: defines.h:96
Definition: defines.h:100
Definition: defines.h:101
Definition: defines.h:102
mode_reason_t
Definition: defines.h:115
DevOptions
Definition: defines.h:288
AltHoldModeState
Definition: defines.h:235
Definition: defines.h:93
aux_sw_func
Definition: defines.h:34
Definition: defines.h:103
tuning_func
Definition: defines.h:138
Definition: defines.h:99
AutoMode
Definition: defines.h:194
Definition: defines.h:97
Definition: defines.h:107
PayloadPlaceStateType
Definition: defines.h:273
GuidedMode
Definition: defines.h:208
SportModeState
Definition: defines.h:251
autopilot_yaw_mode
Definition: defines.h:14
FlipState
Definition: defines.h:259
SmartRTLState
Definition: defines.h:226
Definition: defines.h:98