2016-02-17 21:26:00 -04:00
# pragma once
2011-10-11 06:12:37 -03:00
2015-08-11 03:28:40 -03:00
# include <AP_HAL/AP_HAL_Boards.h>
2012-12-13 20:32:36 -04:00
2011-06-01 02:50:17 -03:00
// Just so that it's completely clear...
2012-08-16 21:50:03 -03:00
# define ENABLED 1
# define DISABLED 0
2011-02-24 01:56:59 -04:00
2012-03-07 03:40:04 -04:00
// this avoids a very common config error
# define ENABLE ENABLED
# define DISABLE DISABLED
2011-09-04 21:15:36 -03:00
2015-03-25 14:58:46 -03:00
// Autopilot Yaw Mode enumeration
enum autopilot_yaw_mode {
AUTO_YAW_HOLD = 0 , // pilot controls the heading
AUTO_YAW_LOOK_AT_NEXT_WP = 1 , // point towards next waypoint (no pilot input accepted)
2017-12-26 00:35:46 -04:00
AUTO_YAW_ROI = 2 , // point towards a location held in roi (no pilot input accepted)
2017-12-25 23:55:42 -04:00
AUTO_YAW_FIXED = 3 , // point towards a particular angle (no pilot input accepted)
2015-03-25 14:58:46 -03:00
AUTO_YAW_LOOK_AHEAD = 4 , // point in the direction the copter is moving
AUTO_YAW_RESETTOARMEDYAW = 5 , // point towards heading at time motors were armed
2017-07-10 09:51:43 -03:00
AUTO_YAW_RATE = 6 , // turn at a specified rate (held in auto_yaw_rate)
2020-04-21 08:50:25 -03:00
AUTO_YAW_CIRCLE = 7 , // use AC_Circle's provided yaw (used during Loiter-Turns commands)
2015-03-25 14:58:46 -03:00
} ;
2014-01-23 01:16:06 -04:00
2011-02-24 01:56:59 -04:00
// Frame types
2013-09-09 03:57:54 -03:00
# define UNDEFINED_FRAME 0
2017-01-09 05:54:18 -04:00
# define MULTICOPTER_FRAME 1
# define HELI_FRAME 2
2011-05-18 20:38:24 -03:00
2011-02-19 03:44:44 -04:00
// HIL enumerations
2012-11-10 01:55:51 -04:00
# define HIL_MODE_DISABLED 0
2014-01-02 01:28:50 -04:00
# define HIL_MODE_SENSORS 1
2011-02-19 03:44:44 -04:00
2015-03-24 17:43:58 -03:00
// Tuning enumeration
enum tuning_func {
2015-04-22 15:10:10 -03:00
TUNING_NONE = 0 , //
TUNING_STABILIZE_ROLL_PITCH_KP = 1 , // stabilize roll/pitch angle controller's P term
TUNING_STABILIZE_YAW_KP = 3 , // stabilize yaw heading controller's P term
TUNING_RATE_ROLL_PITCH_KP = 4 , // body frame roll/pitch rate controller's P term
TUNING_RATE_ROLL_PITCH_KI = 5 , // body frame roll/pitch rate controller's I term
TUNING_YAW_RATE_KP = 6 , // body frame yaw rate controller's P term
TUNING_THROTTLE_RATE_KP = 7 , // throttle rate controller's P term (desired rate to acceleration or motor output)
TUNING_WP_SPEED = 10 , // maximum speed to next way point (0 to 10m/s)
TUNING_LOITER_POSITION_KP = 12 , // loiter distance controller's P term (position error to speed)
TUNING_HELI_EXTERNAL_GYRO = 13 , // TradHeli specific external tail gyro gain
TUNING_ALTITUDE_HOLD_KP = 14 , // altitude hold controller's P term (alt error to desired rate)
TUNING_RATE_ROLL_PITCH_KD = 21 , // body frame roll/pitch rate controller's D term
TUNING_VEL_XY_KP = 22 , // loiter rate controller's P term (speed error to tilt angle)
TUNING_ACRO_RP_KP = 25 , // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
TUNING_YAW_RATE_KD = 26 , // body frame yaw rate controller's D term
TUNING_VEL_XY_KI = 28 , // loiter rate controller's I term (speed error to tilt angle)
TUNING_AHRS_YAW_KP = 30 , // ahrs's compass effect on yaw angle (0 = very low, 1 = very high)
TUNING_AHRS_KP = 31 , // accelerometer effect on roll/pitch angle (0=low)
TUNING_ACCEL_Z_KP = 34 , // accel based throttle controller's P term
TUNING_ACCEL_Z_KI = 35 , // accel based throttle controller's I term
TUNING_ACCEL_Z_KD = 36 , // accel based throttle controller's D term
TUNING_DECLINATION = 38 , // compass declination in radians
TUNING_CIRCLE_RATE = 39 , // circle turn rate in degrees (hard coded to about 45 degrees in either direction)
TUNING_ACRO_YAW_KP = 40 , // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
2016-04-27 08:37:04 -03:00
TUNING_RANGEFINDER_GAIN = 41 , // rangefinder gain
2020-04-21 07:26:15 -03:00
TUNING_EKF_VERTICAL_POS = 42 , // unused
TUNING_EKF_HORIZONTAL_POS = 43 , // unused
TUNING_EKF_ACCEL_NOISE = 44 , // unused
2015-04-22 15:10:10 -03:00
TUNING_RC_FEEL_RP = 45 , // roll-pitch input smoothing
TUNING_RATE_PITCH_KP = 46 , // body frame pitch rate controller's P term
TUNING_RATE_PITCH_KI = 47 , // body frame pitch rate controller's I term
TUNING_RATE_PITCH_KD = 48 , // body frame pitch rate controller's D term
TUNING_RATE_ROLL_KP = 49 , // body frame roll rate controller's P term
TUNING_RATE_ROLL_KI = 50 , // body frame roll rate controller's I term
TUNING_RATE_ROLL_KD = 51 , // body frame roll rate controller's D term
TUNING_RATE_PITCH_FF = 52 , // body frame pitch rate controller FF term
TUNING_RATE_ROLL_FF = 53 , // body frame roll rate controller FF term
TUNING_RATE_YAW_FF = 54 , // body frame yaw rate controller FF term
TUNING_RATE_MOT_YAW_HEADROOM = 55 , // motors yaw headroom minimum
2017-10-04 23:21:23 -03:00
TUNING_RATE_YAW_FILT = 56 , // yaw rate input filter
2019-07-29 04:55:40 -03:00
TUNING_WINCH = 57 , // winch control (not actually a value to be tuned)
2019-10-15 02:38:24 -03:00
TUNING_SYSTEM_ID_MAGNITUDE = 58 // magnitude of the system ID signal
2015-03-24 17:43:58 -03:00
} ;
2011-11-20 09:30:42 -04:00
2013-04-18 03:30:18 -03:00
// Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter
# define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)
# define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl
2013-11-13 13:57:48 -04:00
# 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
2018-08-28 18:05:39 -03:00
# define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters)
2012-12-09 05:04:31 -04:00
2014-01-27 23:21:16 -04:00
// Auto modes
enum AutoMode {
Auto_TakeOff ,
Auto_WP ,
Auto_Land ,
Auto_RTL ,
2014-04-16 04:23:24 -03:00
Auto_CircleMoveToEdge ,
2014-03-22 00:48:54 -03:00
Auto_Circle ,
2014-05-23 02:29:08 -03:00
Auto_Spline ,
2014-10-12 05:06:51 -03:00
Auto_NavGuided ,
2016-11-17 01:19:22 -04:00
Auto_Loiter ,
2018-07-25 00:39:43 -03:00
Auto_LoiterToAlt ,
2016-11-17 01:19:22 -04:00
Auto_NavPayloadPlace ,
2014-01-27 23:21:16 -04:00
} ;
2014-06-02 06:06:11 -03:00
// Guided modes
enum GuidedMode {
2014-08-04 11:08:46 -03:00
Guided_TakeOff ,
2014-06-02 06:06:11 -03:00
Guided_WP ,
2014-11-14 17:26:45 -04:00
Guided_Velocity ,
2015-10-08 08:13:53 -03:00
Guided_PosVel ,
Guided_Angle ,
2014-06-02 06:06:11 -03:00
} ;
2017-07-26 14:14:40 -03:00
// Safe RTL states
2017-09-14 10:21:33 -03:00
enum SmartRTLState {
SmartRTL_WaitForPathCleanup ,
SmartRTL_PathFollow ,
SmartRTL_PreLandPosition ,
SmartRTL_Descend ,
SmartRTL_Land
2017-07-26 14:14:40 -03:00
} ;
2016-11-17 01:19:22 -04:00
enum PayloadPlaceStateType {
PayloadPlaceStateType_FlyToLocation ,
PayloadPlaceStateType_Calibrating_Hover_Start ,
PayloadPlaceStateType_Calibrating_Hover ,
PayloadPlaceStateType_Descending_Start ,
PayloadPlaceStateType_Descending ,
PayloadPlaceStateType_Releasing_Start ,
PayloadPlaceStateType_Releasing ,
PayloadPlaceStateType_Released ,
PayloadPlaceStateType_Ascending_Start ,
PayloadPlaceStateType_Ascending ,
PayloadPlaceStateType_Done ,
} ;
2016-09-12 03:23:53 -03:00
// bit options for DEV_OPTIONS parameter
enum DevOptions {
DevOptionADSBMAVLink = 1 ,
2018-11-05 21:04:00 -04:00
DevOptionVFR_HUDRelativeAlt = 2 ,
2016-09-12 03:23:53 -03:00
} ;
2010-12-19 12:40:33 -04:00
// Logging parameters
2018-03-12 13:32:28 -03:00
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_MOTBATT_MSG ,
LOG_PARAMTUNE_MSG ,
LOG_HELI_MSG ,
LOG_PRECLAND_MSG ,
LOG_GUIDEDTARGET_MSG ,
2019-07-29 04:55:40 -03:00
LOG_SYSIDD_MSG ,
LOG_SYSIDS_MSG ,
2018-03-12 13:32:28 -03:00
} ;
2012-08-16 21:50:03 -03:00
2012-11-10 01:55:51 -04:00
# define MASK_LOG_ATTITUDE_FAST (1<<0)
# define MASK_LOG_ATTITUDE_MED (1<<1)
2012-08-16 21:50:03 -03:00
# define MASK_LOG_GPS (1<<2)
# define MASK_LOG_PM (1<<3)
# define MASK_LOG_CTUN (1<<4)
# define MASK_LOG_NTUN (1<<5)
2013-11-27 03:46:25 -04:00
# define MASK_LOG_RCIN (1<<6)
2013-01-12 11:17:44 -04:00
# define MASK_LOG_IMU (1<<7)
2012-08-16 21:50:03 -03:00
# define MASK_LOG_CMD (1<<8)
2013-01-26 04:20:41 -04:00
# define MASK_LOG_CURRENT (1<<9)
2013-11-27 07:17:16 -04:00
# define MASK_LOG_RCOUT (1<<10)
2012-08-16 21:50:03 -03:00
# define MASK_LOG_OPTFLOW (1<<11)
2015-05-27 01:32:05 -03:00
# define MASK_LOG_PID (1<<12)
2013-02-09 02:24:02 -04:00
# define MASK_LOG_COMPASS (1<<13)
2014-01-13 09:00:11 -04:00
# define MASK_LOG_INAV (1<<14) // deprecated
2012-12-06 11:57:08 -04:00
# define MASK_LOG_CAMERA (1<<15)
2015-03-18 09:08:30 -03:00
# define MASK_LOG_MOTBATT (1UL<<17)
2015-04-19 23:40:04 -03:00
# define MASK_LOG_IMU_FAST (1UL<<18)
2015-05-06 23:09:00 -03:00
# define MASK_LOG_IMU_RAW (1UL<<19)
2014-10-16 21:37:49 -03:00
# define MASK_LOG_ANY 0xFFFF
2012-11-10 01:55:51 -04:00
2013-11-16 00:55:59 -04:00
// Radio failsafe definitions (FS_THR parameter)
2018-01-19 09:44:02 -04:00
# define FS_THR_DISABLED 0
# define FS_THR_ENABLED_ALWAYS_RTL 1
2019-09-21 21:09:18 -03:00
# define FS_THR_ENABLED_CONTINUE_MISSION 2 // Deprecated in 4.0+, now use fs_options
2018-01-19 09:44:02 -04:00
# 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
2013-11-16 00:55:59 -04:00
2016-01-25 19:18:38 -04:00
// GCS failsafe definitions (FS_GCS_ENABLE parameter)
2018-01-19 09:44:02 -04:00
# define FS_GCS_DISABLED 0
# define FS_GCS_ENABLED_ALWAYS_RTL 1
2019-09-21 21:09:18 -03:00
# define FS_GCS_ENABLED_CONTINUE_MISSION 2 // Deprecated in 4.0+, now use fs_options
2018-01-19 09:44:02 -04:00
# define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL 3
# define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND 4
2019-09-21 21:09:18 -03:00
# define FS_GCS_ENABLED_ALWAYS_LAND 5
2016-01-25 19:18:38 -04:00
2015-06-09 23:39:06 -03:00
// EKF failsafe definitions (FS_EKF_ACTION parameter)
# define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe
# define FS_EKF_ACTION_ALTHOLD 2 // switch to ALTHOLD mode on EKF failsafe
# define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3 // switch to Land mode on EKF failsafe even if in a manual flight mode like stabilize
2014-11-14 21:18:17 -04:00
// for mavlink SET_POSITION_TARGET messages
# define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2))
# define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4) | (1<<5))
# define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7) | (1<<8))
2015-04-10 23:57:41 -03:00
# define MAVLINK_SET_POS_TYPE_MASK_FORCE (1<<9)
# define MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE (1<<10)
# define MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE (1<<11)
2014-07-28 19:25:40 -03:00
2015-04-30 03:06:55 -03:00
// for PILOT_THR_BHV parameter
# define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0)
2016-01-06 17:39:36 -04:00
# define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1)
2016-01-11 19:59:42 -04:00
# define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2)