Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/defines.h
Views: 1798
#pragma once12#include <AP_HAL/AP_HAL_Boards.h>34// Frame types5#define UNDEFINED_FRAME 06#define MULTICOPTER_FRAME 17#define HELI_FRAME 289// Tuning enumeration10enum tuning_func {11TUNING_NONE = 0, //12TUNING_STABILIZE_ROLL_PITCH_KP = 1, // stabilize roll/pitch angle controller's P term13TUNING_STABILIZE_YAW_KP = 3, // stabilize yaw heading controller's P term14TUNING_RATE_ROLL_PITCH_KP = 4, // body frame roll/pitch rate controller's P term15TUNING_RATE_ROLL_PITCH_KI = 5, // body frame roll/pitch rate controller's I term16TUNING_YAW_RATE_KP = 6, // body frame yaw rate controller's P term17TUNING_THROTTLE_RATE_KP = 7, // throttle rate controller's P term (desired rate to acceleration or motor output)18TUNING_WP_SPEED = 10, // maximum speed to next way point (0 to 10m/s)19TUNING_LOITER_POSITION_KP = 12, // loiter distance controller's P term (position error to speed)20TUNING_HELI_EXTERNAL_GYRO = 13, // TradHeli specific external tail gyro gain21TUNING_ALTITUDE_HOLD_KP = 14, // altitude hold controller's P term (alt error to desired rate)22TUNING_RATE_ROLL_PITCH_KD = 21, // body frame roll/pitch rate controller's D term23TUNING_VEL_XY_KP = 22, // loiter rate controller's P term (speed error to tilt angle)24TUNING_ACRO_RP_RATE = 25, // acro controller's desired roll and pitch rate in deg/s25TUNING_YAW_RATE_KD = 26, // body frame yaw rate controller's D term26TUNING_VEL_XY_KI = 28, // loiter rate controller's I term (speed error to tilt angle)27TUNING_AHRS_YAW_KP = 30, // ahrs's compass effect on yaw angle (0 = very low, 1 = very high)28TUNING_AHRS_KP = 31, // accelerometer effect on roll/pitch angle (0=low)29TUNING_ACCEL_Z_KP = 34, // accel based throttle controller's P term30TUNING_ACCEL_Z_KI = 35, // accel based throttle controller's I term31TUNING_ACCEL_Z_KD = 36, // accel based throttle controller's D term32TUNING_DECLINATION = 38, // compass declination in radians33TUNING_CIRCLE_RATE = 39, // circle turn rate in degrees (hard coded to about 45 degrees in either direction)34TUNING_ACRO_YAW_RATE = 40, // acro controller's desired yaw rate in deg/s35TUNING_RANGEFINDER_GAIN = 41, // unused36TUNING_EKF_VERTICAL_POS = 42, // unused37TUNING_EKF_HORIZONTAL_POS = 43, // unused38TUNING_EKF_ACCEL_NOISE = 44, // unused39TUNING_RC_FEEL_RP = 45, // roll-pitch input smoothing40TUNING_RATE_PITCH_KP = 46, // body frame pitch rate controller's P term41TUNING_RATE_PITCH_KI = 47, // body frame pitch rate controller's I term42TUNING_RATE_PITCH_KD = 48, // body frame pitch rate controller's D term43TUNING_RATE_ROLL_KP = 49, // body frame roll rate controller's P term44TUNING_RATE_ROLL_KI = 50, // body frame roll rate controller's I term45TUNING_RATE_ROLL_KD = 51, // body frame roll rate controller's D term46TUNING_RATE_PITCH_FF = 52, // body frame pitch rate controller FF term47TUNING_RATE_ROLL_FF = 53, // body frame roll rate controller FF term48TUNING_RATE_YAW_FF = 54, // body frame yaw rate controller FF term49TUNING_RATE_MOT_YAW_HEADROOM = 55, // motors yaw headroom minimum50TUNING_RATE_YAW_FILT = 56, // yaw rate input filter51UNUSED = 57, // was winch control52TUNING_SYSTEM_ID_MAGNITUDE = 58, // magnitude of the system ID signal53TUNING_POS_CONTROL_ANGLE_MAX = 59 // position controller maximum angle54};5556// Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter57#define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)58#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl59#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 last60#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters)616263// Airmode64enum class AirMode {65AIRMODE_NONE,66AIRMODE_DISABLED,67AIRMODE_ENABLED,68};6970// bit options for DEV_OPTIONS parameter71enum DevOptions {72DevOptionADSBMAVLink = 1,73DevOptionVFR_HUDRelativeAlt = 2,74};7576// Logging parameters - only 32 messages are available to the vehicle here.77enum LoggingParameters {78LOG_CONTROL_TUNING_MSG,79LOG_DATA_INT16_MSG,80LOG_DATA_UINT16_MSG,81LOG_DATA_INT32_MSG,82LOG_DATA_UINT32_MSG,83LOG_DATA_FLOAT_MSG,84LOG_PARAMTUNE_MSG,85LOG_HELI_MSG,86LOG_GUIDED_POSITION_TARGET_MSG,87LOG_SYSIDD_MSG,88LOG_SYSIDS_MSG,89LOG_GUIDED_ATTITUDE_TARGET_MSG,90LOG_RATE_THREAD_DT_MSG91};9293#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) // deprecated108#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 0xFFFF115116// Radio failsafe definitions (FS_THR parameter)117#define FS_THR_DISABLED 0118#define FS_THR_ENABLED_ALWAYS_RTL 1119#define FS_THR_ENABLED_CONTINUE_MISSION 2 // Removed in 4.0+, now use fs_options120#define FS_THR_ENABLED_ALWAYS_LAND 3121#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL 4122#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND 5123#define FS_THR_ENABLED_AUTO_RTL_OR_RTL 6124#define FS_THR_ENABLED_BRAKE_OR_LAND 7125126// GCS failsafe definitions (FS_GCS_ENABLE parameter)127#define FS_GCS_DISABLED 0128#define FS_GCS_ENABLED_ALWAYS_RTL 1129#define FS_GCS_ENABLED_CONTINUE_MISSION 2 // Removed in 4.0+, now use fs_options130#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL 3131#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND 4132#define FS_GCS_ENABLED_ALWAYS_LAND 5133#define FS_GCS_ENABLED_AUTO_RTL_OR_RTL 6134#define FS_GCS_ENABLED_BRAKE_OR_LAND 7135136// EKF failsafe definitions (FS_EKF_ACTION parameter)137#define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe138#define FS_EKF_ACTION_ALTHOLD 2 // switch to ALTHOLD mode on EKF failsafe139#define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3 // switch to Land mode on EKF failsafe even if in a manual flight mode like stabilize140141// for PILOT_THR_BHV parameter142#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)145146147