#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#define UNDEFINED_FRAME 0
#define MULTICOPTER_FRAME 1
#define HELI_FRAME 2
enum tuning_func {
TUNING_NONE = 0,
TUNING_STABILIZE_ROLL_PITCH_KP = 1,
TUNING_STABILIZE_YAW_KP = 3,
TUNING_RATE_ROLL_PITCH_KP = 4,
TUNING_RATE_ROLL_PITCH_KI = 5,
TUNING_YAW_RATE_KP = 6,
TUNING_THROTTLE_RATE_KP = 7,
TUNING_WP_SPEED = 10,
TUNING_LOITER_POSITION_KP = 12,
TUNING_HELI_EXTERNAL_GYRO = 13,
TUNING_ALTITUDE_HOLD_KP = 14,
TUNING_RATE_ROLL_PITCH_KD = 21,
TUNING_VEL_XY_KP = 22,
TUNING_ACRO_RP_RATE = 25,
TUNING_YAW_RATE_KD = 26,
TUNING_VEL_XY_KI = 28,
TUNING_AHRS_YAW_KP = 30,
TUNING_AHRS_KP = 31,
TUNING_ACCEL_Z_KP = 34,
TUNING_ACCEL_Z_KI = 35,
TUNING_ACCEL_Z_KD = 36,
TUNING_DECLINATION = 38,
TUNING_CIRCLE_RATE = 39,
TUNING_ACRO_YAW_RATE = 40,
TUNING_RANGEFINDER_GAIN = 41,
TUNING_EKF_VERTICAL_POS = 42,
TUNING_EKF_HORIZONTAL_POS = 43,
TUNING_EKF_ACCEL_NOISE = 44,
TUNING_RC_FEEL_RP = 45,
TUNING_RATE_PITCH_KP = 46,
TUNING_RATE_PITCH_KI = 47,
TUNING_RATE_PITCH_KD = 48,
TUNING_RATE_ROLL_KP = 49,
TUNING_RATE_ROLL_KI = 50,
TUNING_RATE_ROLL_KD = 51,
TUNING_RATE_PITCH_FF = 52,
TUNING_RATE_ROLL_FF = 53,
TUNING_RATE_YAW_FF = 54,
TUNING_RATE_MOT_YAW_HEADROOM = 55,
TUNING_RATE_YAW_FILT = 56,
UNUSED = 57,
TUNING_SYSTEM_ID_MAGNITUDE = 58,
TUNING_POS_CONTROL_ANGLE_MAX = 59,
TUNING_LOITER_MAX_XY_SPEED = 60,
};
#define WP_YAW_BEHAVIOR_NONE 0
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2
#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3
enum class AirMode {
AIRMODE_NONE,
AIRMODE_DISABLED,
AIRMODE_ENABLED,
};
enum DevOptions {
DevOptionADSBMAVLink = 1,
DevOptionVFR_HUDRelativeAlt = 2,
};
enum LoggingParameters {
LOG_CONTROL_TUNING_MSG,
LOG_DATA_INT16_MSG,
LOG_DATA_UINT16_MSG,
LOG_DATA_INT32_MSG,
LOG_DATA_UINT32_MSG,
LOG_DATA_FLOAT_MSG,
LOG_PARAMTUNE_MSG,
LOG_HELI_MSG,
LOG_GUIDED_POSITION_TARGET_MSG,
LOG_SYSIDD_MSG,
LOG_SYSIDS_MSG,
LOG_GUIDED_ATTITUDE_TARGET_MSG,
LOG_RATE_THREAD_DT_MSG
};
#define MASK_LOG_ATTITUDE_FAST (1<<0)
#define MASK_LOG_ATTITUDE_MED (1<<1)
#define MASK_LOG_GPS (1<<2)
#define MASK_LOG_PM (1<<3)
#define MASK_LOG_CTUN (1<<4)
#define MASK_LOG_NTUN (1<<5)
#define MASK_LOG_RCIN (1<<6)
#define MASK_LOG_IMU (1<<7)
#define MASK_LOG_CMD (1<<8)
#define MASK_LOG_CURRENT (1<<9)
#define MASK_LOG_RCOUT (1<<10)
#define MASK_LOG_OPTFLOW (1<<11)
#define MASK_LOG_PID (1<<12)
#define MASK_LOG_COMPASS (1<<13)
#define MASK_LOG_INAV (1<<14)
#define MASK_LOG_CAMERA (1<<15)
#define MASK_LOG_MOTBATT (1UL<<17)
#define MASK_LOG_IMU_FAST (1UL<<18)
#define MASK_LOG_IMU_RAW (1UL<<19)
#define MASK_LOG_VIDEO_STABILISATION (1UL<<20)
#define MASK_LOG_FTN_FAST (1UL<<21)
#define MASK_LOG_ANY 0xFFFF
#define FS_THR_DISABLED 0
#define FS_THR_ENABLED_ALWAYS_RTL 1
#define FS_THR_ENABLED_CONTINUE_MISSION 2
#define FS_THR_ENABLED_ALWAYS_LAND 3
#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL 4
#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND 5
#define FS_THR_ENABLED_AUTO_RTL_OR_RTL 6
#define FS_THR_ENABLED_BRAKE_OR_LAND 7
#define FS_GCS_DISABLED 0
#define FS_GCS_ENABLED_ALWAYS_RTL 1
#define FS_GCS_ENABLED_CONTINUE_MISSION 2
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL 3
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND 4
#define FS_GCS_ENABLED_ALWAYS_LAND 5
#define FS_GCS_ENABLED_AUTO_RTL_OR_RTL 6
#define FS_GCS_ENABLED_BRAKE_OR_LAND 7
#define FS_EKF_ACTION_REPORT_ONLY 0
#define FS_EKF_ACTION_LAND 1
#define FS_EKF_ACTION_ALTHOLD 2
#define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3
#define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0)
#define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1)
#define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2)