Go to the documentation of this file. 10 #define ENABLE ENABLED 11 #define DISABLE DISABLED 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 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) 82 #define UNDEFINED_FRAME 0 83 #define MULTICOPTER_FRAME 1 87 #define HIL_MODE_DISABLED 0 88 #define HIL_MODE_SENSORS 1 183 #define ACRO_TRAINER_DISABLED 0 184 #define ACRO_TRAINER_LEVELING 1 185 #define ACRO_TRAINER_LIMITED 2 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) 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 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 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 418 #define ERROR_CODE_ERROR_RESOLVED 0 419 #define ERROR_CODE_FAILED_TO_INITIALISE 1 420 #define ERROR_CODE_UNHEALTHY 4 422 #define ERROR_CODE_RADIO_LATE_FRAME 2 424 #define ERROR_CODE_FAILSAFE_RESOLVED 0 425 #define ERROR_CODE_FAILSAFE_OCCURRED 1 427 #define ERROR_CODE_COMPASS_FAILED_TO_READ 2 429 #define ERROR_CODE_MAIN_INS_DELAY 1 431 #define ERROR_CODE_CRASH_CHECK_CRASH 1 432 #define ERROR_CODE_CRASH_CHECK_LOSS_OF_CONTROL 2 434 #define ERROR_CODE_FLIP_ABANDONED 2 436 #define ERROR_CODE_MISSING_TERRAIN_DATA 2 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 444 #define ERROR_CODE_PARACHUTE_TOO_LOW 2 445 #define ERROR_CODE_PARACHUTE_LANDED 3 447 #define ERROR_CODE_EKFCHECK_BAD_VARIANCE 2 448 #define ERROR_CODE_EKFCHECK_VARIANCE_CLEARED 0 450 #define ERROR_CODE_BARO_GLITCH 2 452 #define ERROR_CODE_GPS_GLITCH 2 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 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 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 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) 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)