QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APM.h
Go to the documentation of this file.
1#pragma once
2
3namespace APM
4{
5
6enum AUX_FUNC {
7 DO_NOTHING = 0, // aux switch disabled
8 FLIP = 2, // flip
9 SIMPLE_MODE = 3, // change to simple mode
10 RTL = 4, // change to RTL flight mode
11 SAVE_TRIM = 5, // save current position as level
12 SAVE_WP = 7, // save mission waypoint or RTL if in auto mode
13 CAMERA_TRIGGER = 9, // trigger camera servo or relay
14 RANGEFINDER = 10, // allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the ground
15 FENCE = 11, // allow enabling or disabling fence in flight
16 RESETTOARMEDYAW = 12, // UNUSED
17 SUPERSIMPLE_MODE = 13, // change to simple mode in middle, super simple at top
18 ACRO_TRAINER = 14, // low = disabled, middle = leveled, high = leveled and limited
19 SPRAYER = 15, // enable/disable the crop sprayer
20 AUTO = 16, // change to auto flight mode
21 AUTOTUNE_MODE = 17, // auto tune
22 LAND = 18, // change to LAND flight mode
23 GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
24 PARACHUTE_ENABLE = 21, // Parachute enable/disable
25 PARACHUTE_RELEASE = 22, // Parachute release
26 PARACHUTE_3POS = 23, // Parachute disable, enable, release with 3 position switch
27 MISSION_RESET = 24, // Reset auto mission to start from first command
28 ATTCON_FEEDFWD = 25, // enable/disable the roll and pitch rate feed forward
29 ATTCON_ACCEL_LIM = 26, // enable/disable the roll, pitch and yaw accel limiting
30 RETRACT_MOUNT1 = 27, // Retract Mount1
31 RELAY = 28, // Relay pin on/off (only supports first relay)
32 LANDING_GEAR = 29, // Landing gear controller
33 LOST_VEHICLE_SOUND = 30, // Play lost vehicle sound
34 MOTOR_ESTOP = 31, // Emergency Stop Switch
35 MOTOR_INTERLOCK = 32, // Motor On/Off switch
36 BRAKE = 33, // Brake flight mode
37 RELAY2 = 34, // Relay2 pin on/off
38 RELAY3 = 35, // Relay3 pin on/off
39 RELAY4 = 36, // Relay4 pin on/off
40 THROW = 37, // change to THROW flight mode
41 AVOID_ADSB = 38, // enable AP_Avoidance library
42 PRECISION_LOITER = 39, // enable precision loiter
43 AVOID_PROXIMITY = 40, // enable object avoidance using proximity sensors (ie. horizontal lidar)
44 ARMDISARM_UNUSED = 41, // UNUSED
45 SMART_RTL = 42, // change to SmartRTL flight mode
46 INVERTED = 43, // enable inverted flight
47 WINCH_ENABLE = 44, // winch enable/disable
48 WINCH_CONTROL = 45, // winch control
49 RC_OVERRIDE_ENABLE = 46, // enable RC Override
50 USER_FUNC1 = 47, // user function #1
51 USER_FUNC2 = 48, // user function #2
52 USER_FUNC3 = 49, // user function #3
53 LEARN_CRUISE = 50, // learn cruise throttle (Rover)
54 MANUAL = 51, // manual mode
55 ACRO = 52, // acro mode
56 STEERING = 53, // steering mode
57 HOLD = 54, // hold mode
58 GUIDED = 55, // guided mode
59 LOITER = 56, // loiter mode
60 FOLLOW = 57, // follow mode
61 CLEAR_WP = 58, // clear waypoints
62 SIMPLE = 59, // simple mode
63 ZIGZAG = 60, // zigzag mode
64 ZIGZAG_SaveWP = 61, // zigzag save waypoint
65 COMPASS_LEARN = 62, // learn compass offsets
66 SAILBOAT_TACK = 63, // rover sailboat tack
67 REVERSE_THROTTLE = 64, // reverse throttle input
68 GPS_DISABLE = 65, // disable GPS for testing
69 RELAY5 = 66, // Relay5 pin on/off
70 RELAY6 = 67, // Relay6 pin on/off
71 STABILIZE = 68, // stabilize mode
72 POSHOLD = 69, // poshold mode
73 ALTHOLD = 70, // althold mode
74 FLOWHOLD = 71, // flowhold mode
75 CIRCLE = 72, // circle mode
76 DRIFT = 73, // drift mode
77 SAILBOAT_MOTOR_3POS = 74, // Sailboat motoring 3pos
78 SURFACE_TRACKING = 75, // Surface tracking upwards or downwards
79 STANDBY = 76, // Standby mode
80 TAKEOFF = 77, // takeoff
81 RUNCAM_CONTROL = 78, // control RunCam device
82 RUNCAM_OSD_CONTROL = 79, // control RunCam OSD
83 VISODOM_ALIGN = 80, // align visual odometry camera's attitude to AHRS
84 DISARM = 81, // disarm vehicle
85 Q_ASSIST = 82, // disable, enable and force Q assist
86 ZIGZAG_Auto = 83, // zigzag auto switch
87 AIRMODE = 84, // enable / disable airmode for copter
88 GENERATOR = 85, // generator control
89 TER_DISABLE = 86, // disable terrain following in CRUISE/FBWB modes
90 CROW_SELECT = 87, // select CROW mode for diff spoilers;high disables,mid forces progressive
91 SOARING = 88, // three-position switch to set soaring mode
92 LANDING_FLARE = 89, // force flare, throttle forced idle, pitch to LAND_PITCH_DEG, tilts up
93 EKF_SOURCE_SET = 90, // change EKF data source set between primary, secondary and tertiary
94 ARSPD_CALIBRATE= 91, // calibrate airspeed ratio
95 FBWA = 92, // Fly-By-Wire-A
96 RELOCATE_MISSION = 93, // used in separate branch MISSION_RELATIVE
97 VTX_POWER = 94, // VTX power level
98 FBWA_TAILDRAGGER = 95, // enables FBWA taildragger takeoff mode. Once this feature is enabled it will stay enabled until the aircraft goes above TKOFF_TDRAG_SPD1 airspeed, changes mode, or the pitch goes above the initial pitch when this is engaged or goes below 0 pitch. When enabled the elevator will be forced to TKOFF_TDRAG_ELEV. This option allows for easier takeoffs on taildraggers in FBWA mode, and also makes it easier to test auto-takeoff steering handling in FBWA.
99 MODE_SWITCH_RESET = 96, // trigger re-reading of mode switch
100 WIND_VANE_DIR_OFSSET= 97, // flag for windvane direction offset input, used with windvane type 2
101 TRAINING = 98, // mode training
102 AUTO_RTL = 99, // AUTO RTL via DO_LAND_START
103
104 // entries from 100-150 are expected to be developer
105 // options used for testing
106 KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
107 KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
108 CAM_MODE_TOGGLE = 102, // Momentary switch to cycle camera modes
109 EKF_LANE_SWITCH = 103, // trigger lane switch attempt
110 EKF_YAW_RESET = 104, // trigger yaw reset attempt
111 GPS_DISABLE_YAW = 105, // disable GPS yaw for testing
112 DISABLE_AIRSPEED_USE = 106, // equivalent to AIRSPEED_USE 0
113 FW_AUTOTUNE = 107, // fixed wing auto tune
114 QRTL = 108, // QRTL mode
115 CUSTOM_CONTROLLER = 109, // use Custom Controller
116 KILL_IMU3 = 110, // disable third IMU (for IMU failure testing)
117 LOWEHEISER_STARTER = 111, // allows for manually running starter
118 AHRS_TYPE = 112, // change AHRS_EKF_TYPE
119 RETRACT_MOUNT2 = 113, // Retract Mount2
120
121 // if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
122 // also, if you add an option >255, you will need to fix duplicate_options_exist
123
124 // options 150-199 continue user rc switch options
125 CRUISE = 150, // CRUISE mode
126 TURTLE = 151, // Turtle mode - flip over after crash
127 SIMPLE_HEADING_RESET = 152, // reset simple mode reference heading to current
128 ARMDISARM = 153, // arm or disarm vehicle
129 ARMDISARM_AIRMODE = 154, // arm or disarm vehicle enabling airmode
130 TRIM_TO_CURRENT_SERVO_RC = 155, // trim to current servo and RC
131 TORQEEDO_CLEAR_ERR = 156, // clear torqeedo error
132 EMERGENCY_LANDING_EN = 157, //Force long FS action to FBWA for landing out of range
133 OPTFLOW_CAL = 158, // optical flow calibration
134 FORCEFLYING = 159, // enable or disable land detection for GPS based manual modes preventing land detection and maintainting set_throttle_mix_max
135 WEATHER_VANE_ENABLE = 160, // enable/disable weathervaning
136 TURBINE_START = 161, // initialize turbine start sequence
137 FFT_NOTCH_TUNE = 162, // FFT notch tuning function
138 MOUNT_LOCK = 163, // Mount yaw lock vs follow
139 LOG_PAUSE = 164, // Pauses logging if under logging rate control
140 ARM_EMERGENCY_STOP = 165, // ARM on high, MOTOR_ESTOP on low
141 CAMERA_REC_VIDEO = 166, // start recording on high, stop recording on low
142 CAMERA_ZOOM = 167, // camera zoom high = zoom in, middle = hold, low = zoom out
143 CAMERA_MANUAL_FOCUS = 168,// camera manual focus. high = long shot, middle = stop focus, low = close shot
144 CAMERA_AUTO_FOCUS = 169, // camera auto focus
145 QSTABILIZE = 170, // QuadPlane QStabilize mode
146 MAG_CAL = 171, // Calibrate compasses (disarmed only)
147 BATTERY_MPPT_ENABLE = 172,// Battery MPPT Power enable. high = ON, mid = auto (controlled by mppt/batt driver), low = OFF. This effects all MPPTs.
148 PLANE_AUTO_LANDING_ABORT = 173, // Abort Glide-slope or VTOL landing during payload place or do_land type mission items
149 CAMERA_IMAGE_TRACKING = 174, // camera image tracking
150 CAMERA_LENS = 175, // camera lens selection
151 VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method
152 MOUNT_LRF_ENABLE = 177, // mount LRF enable/disable
153 FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint
154 ICE_START_STOP = 179, // AP_ICEngine start stop
155 AUTOTUNE_TEST_GAINS = 180, // auto tune tuning switch to test or revert gains
156 QUICKTUNE = 181, //quicktune 3 position switch
157 AHRS_AUTO_TRIM = 182, // in-flight AHRS autotrim
158 AUTOLAND = 183, //Fixed Wing AUTOLAND Mode
159 SYSTEMID = 184, // system ID as an aux switch
160
161 // inputs from 200 will eventually used to replace RCMAP
162 ROLL = 201, // roll input
163 PITCH = 202, // pitch input
164 THROTTLE = 203, // throttle pilot input
165 YAW = 204, // yaw pilot input
166 MAINSAIL = 207, // mainsail input
167 FLAP = 208, // flap input
168 FWD_THR = 209, // VTOL manual forward throttle
169 AIRBRAKE = 210, // manual airbrake control
170 WALKING_HEIGHT = 211, // walking robot height input
171 MOUNT1_ROLL = 212, // mount1 roll input
172 MOUNT1_PITCH = 213, // mount1 pitch input
173 MOUNT1_YAW = 214, // mount1 yaw input
174 MOUNT2_ROLL = 215, // mount2 roll input
175 MOUNT2_PITCH = 216, // mount3 pitch input
176 MOUNT2_YAW = 217, // mount4 yaw input
177 LOWEHEISER_THROTTLE= 218, // allows for throttle on slider
178 TRANSMITTER_TUNING = 219, // use a transmitter knob or slider for in-flight tuning
179
180 // inputs 248-249 are reserved for the Skybrush fork at
181 // https://github.com/skybrush-io/ardupilot
182
183 // inputs for the use of onboard lua scripting
200
201 // this must be higher than any aux function above
203};
204
205} // namespace APM
Definition APM.h:4
AUX_FUNC
Definition APM.h:6
@ PITCH
Definition APM.h:163
@ RELAY6
Definition APM.h:70
@ AIRMODE
Definition APM.h:87
@ BATTERY_MPPT_ENABLE
Definition APM.h:147
@ USER_FUNC2
Definition APM.h:51
@ FORCEFLYING
Definition APM.h:134
@ KILL_IMU2
Definition APM.h:107
@ LOG_PAUSE
Definition APM.h:139
@ LOWEHEISER_STARTER
Definition APM.h:117
@ TURBINE_START
Definition APM.h:136
@ LANDING_GEAR
Definition APM.h:32
@ GENERATOR
Definition APM.h:88
@ SCRIPTING_5
Definition APM.h:188
@ CRUISE
Definition APM.h:125
@ SYSTEMID
Definition APM.h:159
@ FLIP
Definition APM.h:8
@ SCRIPTING_4
Definition APM.h:187
@ REVERSE_THROTTLE
Definition APM.h:67
@ AUTOLAND
Definition APM.h:158
@ FWD_THR
Definition APM.h:168
@ KILL_IMU1
Definition APM.h:106
@ CAM_MODE_TOGGLE
Definition APM.h:108
@ RTL
Definition APM.h:10
@ TRANSMITTER_TUNING
Definition APM.h:178
@ MOUNT_LRF_ENABLE
Definition APM.h:152
@ ARMDISARM_UNUSED
Definition APM.h:44
@ FW_AUTOTUNE
Definition APM.h:113
@ CLEAR_WP
Definition APM.h:61
@ ARM_EMERGENCY_STOP
Definition APM.h:140
@ FLOWHOLD
Definition APM.h:74
@ SIMPLE
Definition APM.h:62
@ QRTL
Definition APM.h:114
@ SIMPLE_HEADING_RESET
Definition APM.h:127
@ ICE_START_STOP
Definition APM.h:154
@ CAMERA_TRIGGER
Definition APM.h:13
@ BRAKE
Definition APM.h:36
@ MOTOR_INTERLOCK
Definition APM.h:35
@ ACRO
Definition APM.h:55
@ WEATHER_VANE_ENABLE
Definition APM.h:135
@ LOWEHEISER_THROTTLE
Definition APM.h:177
@ PLANE_AUTO_LANDING_ABORT
Definition APM.h:148
@ RELAY2
Definition APM.h:37
@ ATTCON_ACCEL_LIM
Definition APM.h:29
@ MOUNT2_ROLL
Definition APM.h:174
@ WINCH_CONTROL
Definition APM.h:48
@ SUPERSIMPLE_MODE
Definition APM.h:17
@ EKF_LANE_SWITCH
Definition APM.h:109
@ SAILBOAT_MOTOR_3POS
Definition APM.h:77
@ EKF_SOURCE_SET
Definition APM.h:93
@ SCRIPTING_2
Definition APM.h:185
@ RELAY3
Definition APM.h:38
@ MISSION_RESET
Definition APM.h:27
@ TRAINING
Definition APM.h:101
@ PARACHUTE_ENABLE
Definition APM.h:24
@ QSTABILIZE
Definition APM.h:145
@ SAVE_TRIM
Definition APM.h:11
@ CAMERA_REC_VIDEO
Definition APM.h:141
@ SIMPLE_MODE
Definition APM.h:9
@ GUIDED
Definition APM.h:58
@ PRECISION_LOITER
Definition APM.h:42
@ THROW
Definition APM.h:40
@ FBWA
Definition APM.h:95
@ Q_ASSIST
Definition APM.h:85
@ FENCE
Definition APM.h:15
@ SCRIPTING_7
Definition APM.h:190
@ SCRIPTING_1
Definition APM.h:184
@ RETRACT_MOUNT2
Definition APM.h:119
@ RELAY
Definition APM.h:31
@ SCRIPTING_16
Definition APM.h:199
@ ACRO_TRAINER
Definition APM.h:18
@ DISABLE_AIRSPEED_USE
Definition APM.h:112
@ LOITER
Definition APM.h:59
@ VTX_POWER
Definition APM.h:97
@ WALKING_HEIGHT
Definition APM.h:170
@ VISODOM_ALIGN
Definition APM.h:83
@ AVOID_ADSB
Definition APM.h:41
@ CROW_SELECT
Definition APM.h:90
@ MOUNT1_YAW
Definition APM.h:173
@ EKF_YAW_RESET
Definition APM.h:110
@ TURTLE
Definition APM.h:126
@ LEARN_CRUISE
Definition APM.h:53
@ INVERTED
Definition APM.h:46
@ STANDBY
Definition APM.h:79
@ GPS_DISABLE
Definition APM.h:68
@ VFWD_THR_OVERRIDE
Definition APM.h:151
@ PARACHUTE_3POS
Definition APM.h:26
@ SCRIPTING_8
Definition APM.h:191
@ SMART_RTL
Definition APM.h:45
@ SCRIPTING_14
Definition APM.h:197
@ STEERING
Definition APM.h:56
@ MOUNT1_ROLL
Definition APM.h:171
@ RUNCAM_CONTROL
Definition APM.h:81
@ MOUNT2_PITCH
Definition APM.h:175
@ USER_FUNC3
Definition APM.h:52
@ RETRACT_MOUNT1
Definition APM.h:30
@ MOUNT_LOCK
Definition APM.h:138
@ DO_NOTHING
Definition APM.h:7
@ AIRBRAKE
Definition APM.h:169
@ TER_DISABLE
Definition APM.h:89
@ AUTO_RTL
Definition APM.h:102
@ WINCH_ENABLE
Definition APM.h:47
@ AUTOTUNE_TEST_GAINS
Definition APM.h:155
@ DRIFT
Definition APM.h:76
@ ARSPD_CALIBRATE
Definition APM.h:94
@ HOLD
Definition APM.h:57
@ RESETTOARMEDYAW
Definition APM.h:16
@ CAMERA_MANUAL_FOCUS
Definition APM.h:143
@ SCRIPTING_9
Definition APM.h:192
@ SCRIPTING_13
Definition APM.h:196
@ AUTOTUNE_MODE
Definition APM.h:21
@ CAMERA_IMAGE_TRACKING
Definition APM.h:149
@ GPS_DISABLE_YAW
Definition APM.h:111
@ CAMERA_LENS
Definition APM.h:150
@ AHRS_AUTO_TRIM
Definition APM.h:157
@ AVOID_PROXIMITY
Definition APM.h:43
@ ZIGZAG
Definition APM.h:63
@ ARMDISARM
Definition APM.h:128
@ MOTOR_ESTOP
Definition APM.h:34
@ LAND
Definition APM.h:22
@ AUTO
Definition APM.h:20
@ MAINSAIL
Definition APM.h:166
@ GRIPPER
Definition APM.h:23
@ RELOCATE_MISSION
Definition APM.h:96
@ USER_FUNC1
Definition APM.h:50
@ AUX_FUNCTION_MAX
Definition APM.h:202
@ QUICKTUNE
Definition APM.h:156
@ SAVE_WP
Definition APM.h:12
@ SAILBOAT_TACK
Definition APM.h:66
@ RELAY5
Definition APM.h:69
@ POSHOLD
Definition APM.h:72
@ CAMERA_AUTO_FOCUS
Definition APM.h:144
@ AHRS_TYPE
Definition APM.h:118
@ OPTFLOW_CAL
Definition APM.h:133
@ SCRIPTING_12
Definition APM.h:195
@ ZIGZAG_Auto
Definition APM.h:86
@ MAG_CAL
Definition APM.h:146
@ FLIGHTMODE_PAUSE
Definition APM.h:153
@ THROTTLE
Definition APM.h:164
@ RUNCAM_OSD_CONTROL
Definition APM.h:82
@ RC_OVERRIDE_ENABLE
Definition APM.h:49
@ SOARING
Definition APM.h:91
@ CAMERA_ZOOM
Definition APM.h:142
@ TAKEOFF
Definition APM.h:80
@ EMERGENCY_LANDING_EN
Definition APM.h:132
@ LANDING_FLARE
Definition APM.h:92
@ SCRIPTING_11
Definition APM.h:194
@ RANGEFINDER
Definition APM.h:14
@ SPRAYER
Definition APM.h:19
@ FOLLOW
Definition APM.h:60
@ ZIGZAG_SaveWP
Definition APM.h:64
@ STABILIZE
Definition APM.h:71
@ MOUNT2_YAW
Definition APM.h:176
@ WIND_VANE_DIR_OFSSET
Definition APM.h:100
@ SURFACE_TRACKING
Definition APM.h:78
@ COMPASS_LEARN
Definition APM.h:65
@ DISARM
Definition APM.h:84
@ SCRIPTING_10
Definition APM.h:193
@ ALTHOLD
Definition APM.h:73
@ KILL_IMU3
Definition APM.h:116
@ MANUAL
Definition APM.h:54
@ SCRIPTING_15
Definition APM.h:198
@ MODE_SWITCH_RESET
Definition APM.h:99
@ ARMDISARM_AIRMODE
Definition APM.h:129
@ CUSTOM_CONTROLLER
Definition APM.h:115
@ ROLL
Definition APM.h:162
@ FBWA_TAILDRAGGER
Definition APM.h:98
@ PARACHUTE_RELEASE
Definition APM.h:25
@ RELAY4
Definition APM.h:39
@ FFT_NOTCH_TUNE
Definition APM.h:137
@ SCRIPTING_6
Definition APM.h:189
@ CIRCLE
Definition APM.h:75
@ LOST_VEHICLE_SOUND
Definition APM.h:33
@ YAW
Definition APM.h:165
@ FLAP
Definition APM.h:167
@ TRIM_TO_CURRENT_SERVO_RC
Definition APM.h:130
@ TORQEEDO_CLEAR_ERR
Definition APM.h:131
@ SCRIPTING_3
Definition APM.h:186
@ ATTCON_FEEDFWD
Definition APM.h:28
@ MOUNT1_PITCH
Definition APM.h:172