2016-03-17 15:02:55 -03:00
# pragma once
2015-12-30 18:57:56 -04:00
# include <AP_HAL/AP_HAL_Boards.h>
// Just so that it's completely clear...
# define ENABLED 1
# define DISABLED 0
// this avoids a very common config error
# define ENABLE ENABLED
# define DISABLE DISABLED
2016-02-28 20:13:06 -04:00
# define BOTTOM_DETECTOR_TRIGGER_SEC 1.0
# define SURFACE_DETECTOR_TRIGGER_SEC 1.0
2017-03-08 22:59:39 -04:00
enum AutoSurfaceState {
AUTO_SURFACE_STATE_GO_TO_LOCATION ,
AUTO_SURFACE_STATE_ASCEND
} ;
2015-12-30 18:57:56 -04:00
// Autopilot Yaw Mode enumeration
enum autopilot_yaw_mode {
2017-02-07 20:42:28 -04:00
AUTO_YAW_HOLD = 0 , // pilot controls the heading
AUTO_YAW_LOOK_AT_NEXT_WP = 1 , // point towards next waypoint (no pilot input accepted)
AUTO_YAW_ROI = 2 , // point towards a location held in roi_WP (no pilot input accepted)
AUTO_YAW_LOOK_AT_HEADING = 3 , // point towards a particular angle (not pilot input accepted)
2017-02-10 13:46:54 -04:00
AUTO_YAW_LOOK_AHEAD = 4 , // point in the direction the vehicle is moving
2017-02-07 20:42:28 -04:00
AUTO_YAW_RESETTOARMEDYAW = 5 , // point towards heading at time motors were armed
2017-02-03 17:33:27 -04:00
AUTO_YAW_CORRECT_XTRACK = 6 // steer the sub in order to correct for crosstrack error during line following
2015-12-30 18:57:56 -04:00
} ;
// Auto Pilot Modes enumeration
2016-04-18 01:38:21 -03:00
enum control_mode_t {
2016-09-01 12:10:11 -03:00
STABILIZE = 0 , // manual angle with manual depth/throttle
ACRO = 1 , // manual body-frame angular rate with manual depth/throttle
ALT_HOLD = 2 , // manual angle with automatic depth/throttle
2017-05-22 21:14:10 -03:00
AUTO = 3 , // fully automatic waypoint control using mission commands
GUIDED = 4 , // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
CIRCLE = 7 , // automatic circular flight with automatic throttle
2016-09-01 12:10:11 -03:00
SURFACE = 9 , // automatically return to surface, pilot maintains horizontal control
2015-12-30 18:57:56 -04:00
POSHOLD = 16 , // automatic position hold with manual override, with automatic throttle
2017-02-03 17:33:27 -04:00
MANUAL = 19 // Pass-through input with no stabilization
2015-12-30 18:57:56 -04:00
} ;
2016-04-18 01:38:21 -03:00
enum mode_reason_t {
MODE_REASON_UNKNOWN = 0 ,
MODE_REASON_TX_COMMAND ,
MODE_REASON_GCS_COMMAND ,
MODE_REASON_RADIO_FAILSAFE ,
MODE_REASON_BATTERY_FAILSAFE ,
MODE_REASON_GCS_FAILSAFE ,
MODE_REASON_EKF_FAILSAFE ,
MODE_REASON_GPS_GLITCH ,
MODE_REASON_MISSION_END ,
2017-03-09 13:25:54 -04:00
MODE_REASON_THROTTLE_SURFACE_ESCAPE ,
2016-05-03 01:45:37 -03:00
MODE_REASON_FENCE_BREACH ,
2017-02-03 17:33:27 -04:00
MODE_REASON_TERRAIN_FAILSAFE ,
MODE_REASON_SURFACE_COMPLETE ,
2017-04-15 02:03:56 -03:00
MODE_REASON_LEAK_FAILSAFE ,
MODE_REASON_BAD_DEPTH
2016-04-18 01:38:21 -03:00
} ;
2015-12-30 18:57:56 -04:00
// Acro Trainer types
# define ACRO_TRAINER_DISABLED 0
# define ACRO_TRAINER_LEVELING 1
# define ACRO_TRAINER_LIMITED 2
// RC Feel roll/pitch definitions
# define RC_FEEL_RP_VERY_SOFT 0
# define RC_FEEL_RP_SOFT 25
# define RC_FEEL_RP_MEDIUM 50
# define RC_FEEL_RP_CRISP 75
# define RC_FEEL_RP_VERY_CRISP 100
// 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
# 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
# define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicotpers)
2017-02-03 17:33:27 -04:00
# define WP_YAW_BEHAVIOR_CORRECT_XTRACK 4 // point towards intermediate position target during line following
2015-12-30 18:57:56 -04:00
// Auto modes
enum AutoMode {
Auto_WP ,
Auto_CircleMoveToEdge ,
Auto_Circle ,
Auto_Spline ,
Auto_NavGuided ,
2017-02-07 20:42:28 -04:00
Auto_Loiter ,
2017-02-03 17:33:27 -04:00
Auto_TerrainRecover
2015-12-30 18:57:56 -04:00
} ;
// Guided modes
enum GuidedMode {
Guided_WP ,
Guided_Velocity ,
Guided_PosVel ,
Guided_Angle ,
} ;
// RTL states
enum RTLState {
RTL_InitialClimb ,
RTL_ReturnHome ,
RTL_LoiterAtHome ,
RTL_FinalDescent ,
RTL_Land
} ;
// Logging parameters
# define TYPE_AIRSTART_MSG 0x00
# define TYPE_GROUNDSTART_MSG 0x01
# define LOG_CONTROL_TUNING_MSG 0x04
# define LOG_NAV_TUNING_MSG 0x05
# define LOG_PERFORMANCE_MSG 0x06
# define LOG_OPTFLOW_MSG 0x0C
# define LOG_EVENT_MSG 0x0D
# define LOG_ERROR_MSG 0x13
# define LOG_DATA_INT16_MSG 0x14
# define LOG_DATA_UINT16_MSG 0x15
# define LOG_DATA_INT32_MSG 0x16
# define LOG_DATA_UINT32_MSG 0x17
# define LOG_DATA_FLOAT_MSG 0x18
# define LOG_MOTBATT_MSG 0x1E
# define LOG_PARAMTUNE_MSG 0x1F
2017-02-03 17:33:27 -04:00
# define LOG_GUIDEDTARGET_MSG 0x22
2016-11-17 01:12:06 -04:00
# define LOG_PROXIMITY_MSG 0x24
2015-12-30 18:57:56 -04:00
# 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_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_ANY 0xFFFF
// DATA - event logging
# define DATA_AP_STATE 7
# define DATA_SYSTEM_TIME_SET 8
# define DATA_ARMED 10
# define DATA_DISARMED 11
# define DATA_LOST_GPS 19
# define DATA_SET_HOME 25
# define DATA_SAVE_TRIM 38
# define DATA_SAVEWP_ADD_WP 39
# define DATA_FENCE_ENABLE 41
# define DATA_FENCE_DISABLE 42
# define DATA_ACRO_TRAINER_DISABLED 43
# define DATA_ACRO_TRAINER_LEVELING 44
# define DATA_ACRO_TRAINER_LIMITED 45
2016-11-17 01:12:06 -04:00
# define DATA_GRIPPER_GRAB 46
# define DATA_GRIPPER_RELEASE 47
2015-12-30 18:57:56 -04:00
# define DATA_EKF_ALT_RESET 60
2017-03-09 13:25:54 -04:00
# define DATA_SURFACE_CANCELLED_BY_PILOT 61
2016-07-05 21:18:58 -03:00
# define DATA_EKF_YAW_RESET 62
2017-03-08 18:16:51 -04:00
# define DATA_SURFACED 63
# define DATA_NOT_SURFACED 64
# define DATA_BOTTOMED 65
# define DATA_NOT_BOTTOMED 66
2015-12-30 18:57:56 -04:00
// Centi-degrees to radians
# define DEGX100 5729.57795f
// Error message sub systems and error codes
# define ERROR_SUBSYSTEM_MAIN 1
2017-01-30 14:10:22 -04:00
# define ERROR_SUBSYSTEM_INPUT 2
2015-12-30 18:57:56 -04:00
# define ERROR_SUBSYSTEM_COMPASS 3
# define ERROR_SUBSYSTEM_OPTFLOW 4
# define ERROR_SUBSYSTEM_FAILSAFE_RADIO 5
# define ERROR_SUBSYSTEM_FAILSAFE_BATT 6
# define ERROR_SUBSYSTEM_FAILSAFE_GPS 7 // not used
# define ERROR_SUBSYSTEM_FAILSAFE_GCS 8
# define ERROR_SUBSYSTEM_FAILSAFE_FENCE 9
# define ERROR_SUBSYSTEM_FLIGHT_MODE 10
# define ERROR_SUBSYSTEM_GPS 11 // not used
# define ERROR_SUBSYSTEM_CRASH_CHECK 12
# define ERROR_SUBSYSTEM_EKFCHECK 16
# define ERROR_SUBSYSTEM_FAILSAFE_EKFINAV 17
# define ERROR_SUBSYSTEM_BARO 18
# define ERROR_SUBSYSTEM_CPU 19
2016-05-03 01:45:37 -03:00
# define ERROR_SUBSYSTEM_TERRAIN 21
# define ERROR_SUBSYSTEM_NAVIGATION 22
# define ERROR_SUBSYSTEM_FAILSAFE_TERRAIN 23
2016-11-21 18:20:30 -04:00
# define ERROR_SUBSYSTEM_FAILSAFE_LEAK 24
2017-04-15 02:03:56 -03:00
# define ERROR_SUBSYSTEM_FAILSAFE_SENSORS 25
2015-12-30 18:57:56 -04:00
// general error codes
# define ERROR_CODE_ERROR_RESOLVED 0
# define ERROR_CODE_FAILED_TO_INITIALISE 1
# define ERROR_CODE_UNHEALTHY 4
// subsystem specific error codes -- radio
# define ERROR_CODE_RADIO_LATE_FRAME 2
// subsystem specific error codes -- failsafe_thr, batt, gps
# define ERROR_CODE_FAILSAFE_RESOLVED 0
# define ERROR_CODE_FAILSAFE_OCCURRED 1
// subsystem specific error codes -- compass
# define ERROR_CODE_COMPASS_FAILED_TO_READ 2
// subsystem specific error codes -- main
# define ERROR_CODE_MAIN_INS_DELAY 1
// subsystem specific error codes -- crash checker
# define ERROR_CODE_CRASH_CHECK_CRASH 1
# define ERROR_CODE_CRASH_CHECK_LOSS_OF_CONTROL 2
2016-05-03 01:45:37 -03:00
// subsystem specific error codes -- terrain
# define ERROR_CODE_MISSING_TERRAIN_DATA 2
// subsystem specific error codes -- navigation
# define ERROR_CODE_FAILED_TO_SET_DESTINATION 2
# define ERROR_CODE_RESTARTED_RTL 3
# define ERROR_CODE_FAILED_CIRCLE_INIT 4
2016-05-22 21:50:44 -03:00
# define ERROR_CODE_DEST_OUTSIDE_FENCE 5
2015-12-30 18:57:56 -04:00
// EKF check definitions
# define ERROR_CODE_EKFCHECK_BAD_VARIANCE 2
# define ERROR_CODE_EKFCHECK_VARIANCE_CLEARED 0
2017-04-15 02:03:56 -03:00
2015-12-30 18:57:56 -04:00
// Baro specific error codes
2017-04-15 02:03:56 -03:00
# define ERROR_CODE_BAD_DEPTH 0
2015-12-30 18:57:56 -04:00
2017-03-24 14:01:15 -03:00
//////////////////////////////////////////////////////////////////////////////
// Battery monitoring
//
# ifndef FS_BATT_VOLTAGE_DEFAULT
# define FS_BATT_VOLTAGE_DEFAULT 0 // default battery voltage below which failsafe will be triggered
# endif
# ifndef FS_BATT_MAH_DEFAULT
# define FS_BATT_MAH_DEFAULT 0 // default battery capacity (in mah) below which failsafe will be triggered
# endif
// GCS failsafe
# ifndef FS_GCS
# define FS_GCS DISABLED
# endif
# ifndef FS_GCS_TIMEOUT_MS
# define FS_GCS_TIMEOUT_MS 2500 // gcs failsafe triggers after 5 seconds with no GCS heartbeat
# endif
// missing terrain data failsafe
# ifndef FS_TERRAIN_TIMEOUT_MS
# define FS_TERRAIN_TIMEOUT_MS 1000 // 1 second of unhealthy rangefinder and/or missing terrain data will trigger failsafe
# endif
//////////////////////////////////////////////////////////////////////////////
// EKF Failsafe
// EKF failsafe definitions (FS_EKF_ENABLE parameter)
2017-04-08 11:36:16 -03:00
# define FS_EKF_ACTION_DISABLED 0 // Disabled
# define FS_EKF_ACTION_WARN_ONLY 1 // Send warning to gcs
# define FS_EKF_ACTION_DISARM 2 // Disarm
2017-03-24 14:01:15 -03:00
# ifndef FS_EKF_ACTION_DEFAULT
# define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_DISABLED // EKF failsafe
# endif
# ifndef FS_EKF_THRESHOLD_DEFAULT
# define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered
# endif
2015-12-30 18:57:56 -04:00
// Battery failsafe definitions (FS_BATT_ENABLE parameter)
# define FS_BATT_DISABLED 0 // battery failsafe disabled
2017-03-24 15:25:30 -03:00
# define FS_BATT_WARN_ONLY 1 // only warn gcs on battery failsafe
# define FS_BATT_DISARM 2 // disarm on battery failsafe
# define FS_BATT_SURFACE 3 // switch to SURFACE mode on battery failsafe
2015-12-30 18:57:56 -04:00
2016-04-18 01:38:21 -03:00
// GCS failsafe definitions (FS_GCS_ENABLE parameter)
2017-02-03 17:33:27 -04:00
# define FS_GCS_DISABLED 0 // Disabled
# define FS_GCS_WARN_ONLY 1 // Only send warning to gcs (only useful with multiple gcs links)
# define FS_GCS_DISARM 2 // Disarm
# define FS_GCS_HOLD 3 // Switch depth hold mode or poshold mode if available
# define FS_GCS_SURFACE 4 // Switch to surface mode
2016-08-26 16:27:28 -03:00
// Leak failsafe definitions (FS_LEAK_ENABLE parameter)
2017-02-03 17:33:27 -04:00
# define FS_LEAK_DISABLED 0 // Disabled
# define FS_LEAK_WARN_ONLY 1 // Only send waring to gcs
# define FS_LEAK_SURFACE 2 // Switch to surface mode
2016-08-26 16:27:28 -03:00
2016-09-11 18:49:19 -03:00
// Internal pressure failsafe threshold (FS_PRESS_MAX parameter)
2017-02-03 17:33:27 -04:00
# define FS_PRESS_MAX_DEFAULT 105000 // Maximum internal pressure in pascal before failsafe is triggered
2016-09-11 18:49:19 -03:00
// Internal pressure failsafe definitions (FS_PRESS_ENABLE parameter)
2017-02-03 17:33:27 -04:00
# define FS_PRESS_DISABLED 0
# define FS_PRESS_WARN_ONLY 1
2016-09-11 18:49:19 -03:00
// Internal temperature failsafe threshold (FS_TEMP_MAX parameter)
2017-02-03 17:33:27 -04:00
# define FS_TEMP_MAX_DEFAULT 62 // Maximum internal pressure in degrees C before failsafe is triggered
2016-09-11 18:49:19 -03:00
// Internal temperature failsafe definitions (FS_TEMP_ENABLE parameter)
2017-02-03 17:33:27 -04:00
# define FS_TEMP_DISABLED 0
# define FS_TEMP_WARN_ONLY 1
2017-02-07 20:42:28 -04:00
2017-03-24 17:30:28 -03:00
// Crash failsafe options
# define FS_CRASH_DISABLED 0
# define FS_CRASH_WARN_ONLY 1
# define FS_CRASH_DISARM 2
2017-02-07 20:42:28 -04:00
// Terrain failsafe actions for AUTO mode
2017-02-03 17:33:27 -04:00
# define FS_TERRAIN_DISARM 0
# define FS_TERRAIN_HOLD 1
# define FS_TERRAIN_SURFACE 2
2017-02-07 20:42:28 -04:00
2017-04-14 18:23:59 -03:00
// Pilot input failsafe actions
# define FS_PILOT_INPUT_DISABLED 0
# define FS_PILOT_INPUT_WARN_ONLY 1
# define FS_PILOT_INPUT_DISARM 2
2017-02-07 20:42:28 -04:00
// Amount of time to attempt recovery of valid rangefinder data before
// initiating terrain failsafe action
# define FS_TERRAIN_RECOVER_TIMEOUT_MS 10000
2016-09-11 18:49:19 -03:00
2015-12-30 18:57:56 -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))
# 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)