Mission Commands¶
This article describes the mission commands that are supported by Copter, Plane and Rover when switched into Auto mode. A better list just for Copter can be found here
Overview¶
The MAVLink protocol defines a large number of
MAV_CMD
waypoint command types (sent in a MAVLink_mission_item_message
).
ArduPilot implements handling for the subset of these commands and
command parameters that are most relevant and meaningful for each of
the vehicles. Unsupported commands that are sent to a particular
autopilot will simply be dropped.
This article lists and describes the commands and command-parameters that are supported on each of the vehicle types. Any parameter that is “grey” is not supported by the autopilot and will be ignored. They are still documented to make it clear which properties are supported by the MAV_CMD protocol are not implemented by the vehicle.
Some commands and command parameters are not implemented because they are not relevant for particular vehicle types (for example “MAV_CMD_NAV_TAKEOFF” command makes sense for Plane and Copter but not Rover and the pitch parameter only makes sense for Plane). There are also some potentially useful command parameters that are not handled because there is a limit to the message size, and a decision has been made to prioritize some parameters over others.
Note
There is additional information about the supported commands on Copter (from a Mission Planner perspective) in the Copter Mission Command List.
Types of commands¶
There are several different types of commands that can be used within missions:
Navigation commands are used to control the movement of the vehicle, including takeoff, moving to and around waypoints, changing altitude, and landing.
DO commands are for auxiliary functions and do not affect the vehicle’s position (for example, setting the camera trigger distance, or setting a servo value).
Condition commands are used to delay DO commands until some condition is met, for example, the UAV reaches a certain altitude or distance from the waypoint.
During a mission at most one “Navigation” command and one “Do” or “Condition” command can be running at one time. A typical mission might set a waypoint (NAV command), add a CONDITION command that doesn’t complete until a certain distance from the destination (MAV_CMD_CONDITION_DISTANCE), and then add a number of DO commands that are executed sequentially (for example MAV_CMD_DO_SET_CAM_TRIGG_DIST to take pictures at regular intervals) when the condition completes.
Note
CONDITION and DO commands are associated with the preceding NAV command: if the UAV reaches the next waypoint before these commands are executed, the next NAV command is loaded and they will be skipped.
Frames of reference¶
Many of the commands (in particular the NAV_ commands) include position/location information. The information is provided relative to a particular “frame of reference”, which is specified in the message’s Frames of reference field. Copter and Rover Mission use MAV_CMD_DO_SET_HOME command to set the “home position” in the global coordinate frame (MAV_FRAME_GLOBAL), WGS84 coordinate system, where the altitude is relative to mean sea level. All other commands use the MAV_FRAME_GLOBAL_RELATIVE_ALT frame, which uses the same latitude and longitude, but sets altitude as relative to the home position (home altitude = 0).
Plane commands can additionally use MAV_FRAME_GLOBAL_TERRAIN_ALT frame of reference. This again has the same WGS84 frame of reference for latitude/longitude, but specifies altitude relative to ground height (as defined in a terrain database).
Note
The other frame types are defined in the MAVLink protocol (see MAV_FRAME) are not supported for mission commands.
How accurate is the information?¶
If a command or parameter is marked as supported then it is likely (but not guaranteed) that it will behave as indicated. If a command or parameter is not listed (or marked as not supported) then it is extremely likely that it is not supported on ArduPilot.
The reason for this is that the information was predominantly inferred by inspecting the command handlers for messages:
The switch statement in AP_Mission::mavlink_to_mission_cmd was inspected to determine which commands are handled by all vehicle platforms, and which parameters from the message are stored.
The command handler switch for each vehicle type (Plane, Copter, Rover) tells us which commands are likely to be supported in each vehicle and which parameters are passed to the handler.
The above checks give a very accurate picture of what commands and parameters are not supported. They give a fairly accurate picture of what commands/parameters are likely to be supported. However, this indication is not guaranteed to be accurate because a command handler could just throw away all the information (and we have not fully checked all of these).
In addition to the above checks, we have also merged information from the Copter Mission Command List.
How to interpret the command parameters¶
The parameters for each command are listed in a table. The parameters that are “greyed out” are not supported. The command field column (param name) uses “bold” text to indicate those parameters that are defined in the protocol (normal text is used for “empty” parameters).
This allows users/developers to see both what is supported, and what protocol fields are not supported in ArduPilot.
Using this information with a GCS¶
Mission Planner (MP) exposes the full subset of commands and
parameters supported by ArduPilot, filtered to display just those
relevant to the currently connected vehicle. Mapping the MP commands to
this documentation is easy, because it simply names commands using a
cut-down version of the full command name (e.g. DO_SET_SERVO
rather
than the full command name: MAV_CMD_DO_SET_SERVO
). In addition, this
document conveniently lists the column label used by Mission Planner
alongside each of the parameters.
Other GCSs (APM Planner 2, Tower etc.) may support some other subset of commands/parameters and use alternative names/labels for them. In most cases, the mapping should be obvious.
Commands supported by Plane¶
This list of commands was inferred from the command handler in /ArduPlane/commands_logic.cpp.
MAV_CMD_DO_DIGICAM_CONFIGURE (Camera enabled only)
MAV_CMD_DO_DIGICAM_CONTROL (Camera enabled only)
MAV_CMD_DO_SET_CAM_TRIGG_DIST (Camera enabled only)
MAV_CMD_DO_SET_ROI (Gimbal/mount enabled only)
MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW (Gimbal/mount enabled only)
Conditional commands¶
Conditional commands control the execution of _DO_ commands. For example, a conditional command can prevent DO commands from executing based on a time delay, until the vehicle is at a certain altitude, or at a specified distance from the next target position.
A conditional command may not be complete before reaching the next waypoint. In this case, any unexecuted _DO_ commands associated with the last waypoint will be skipped.
MAV_CMD_CONDITION_DELAY¶
Supported by: All vehicles.
After reaching a waypoint, delay the execution of the next conditional “_DO_” command for the specified number of seconds (e.g. MAV_CMD_DO_SET_ROI).
Note
This command does not stop the vehicle. If the vehicle reaches the next waypoint before the delay timer completes, the delayed “_DO_” commands will never trigger.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Time (sec) | Delay in seconds (decimal). |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
Mission planner screenshots
In the example above, Command #4 (DO_SET_ROI
) is delayed so that it
starts 5 seconds after the vehicle has passed Waypoint #2.
MAV_CMD_CONDITION_DISTANCE¶
Supported by: All vehicles.
Delays the start of the next “_DO_
” command until the vehicle is
within the specified number of meters of the next waypoint.
Note
This command does not stop the vehicle: it only affects DO commands.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Dist (m) | Distance from the next waypoint before DO commands are executed (meters). |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
Mission planner screenshots
In the example above, Command #4 (DO_SET_ROI
) is delayed so that it
only starts once the vehicle is within 50m of waypoint #5.
DO commands¶
The “DO” or “Now” commands are executed once to perform some action. All the DO commands associated with a waypoint are executed immediately.
MAV_CMD_DO_CHANGE_SPEED¶
Supported by: Copter, Plane, Rover.
Change the target horizontal speed (airspeed or groundspeed) and/or the vehicle’s throttle. If the airspeed option is selected, this changes the AIRSPEED_CRUISE parameter during the flight until reboot or mode is changed to CRUISE or FBWB. If the groundspeed option is used, then MIN_GROUNDSPEED parameter is changed to this value until rebooted or changed by this command again. If the throttle field is non-zero and equal to or below 100, then the TRIM_THROTTLE parameter is changed until reboot or changed by this command again.
Note
Speed changes only have an effect if an airspeed sensor is present, healthy, and in use. TRIM_THROTTLE changes impacts only flight with airspeed sensor not in use.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Type | Speed type (0=Airspeed, 1=Ground Speed). |
param2 | Speed (m/s) | Target speed (m/s). If airspeed, a value below or above min/max airspeed limits results in no change. a value of -2 uses :ref:`AIRSPEED_CRUISE |
param3 | Throttle(%) | Throttle as a percentage (0-100%). A value of 0 or negative indicates no change. |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_DO_SET_HOME¶
Supported by: All vehicles.
Sets the home location either as the current location or at the location specified in the command. For SITL work, altitude input here needs to be with reference to absolute altitude, taking into account SRTM elevation.
Note
For Plane and Rover, if a good GPS fix cannot be obtained the location specified in the command is used.
For Copter, the command will also try to use the current position if all the location parameters are set to 0. The location information in the command is only used if it is close to the EKF origin.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Current | Set home location: 1=Set home as current location. 0=Use location specified in message parameters. |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Lat | Target home latitude (if param1=0 ) |
param6 | Lon | Target home longitude (if param1=0 ) |
param7 | Alt | Target home altitude (if param1=0 ) |
Mission planner screenshots
MAV_CMD_DO_SET_RELAY¶
Supported by: All vehicles.
Set a Relay pin’s voltage high (on) or low (off).
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Relay No | Relay number. |
param2 | off(0)/on(1) | Set relay state: 1: Set relay high/on (3.3V on Pixhawk, 5V on APM). 0: Set relay low/off (0v) any other value toggles the relay |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
Mission planner screenshots
MAV_CMD_DO_REPEAT_RELAY¶
Supported by: All vehicles.
Toggle the Relay pin’s voltage/state a specified number of times with a given period. Toggling the Relay will turn an off relay on and vice versa
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Relay No | Relay number. |
param2 | Repeat # | Cycle count - the number of times the relay should be toggled |
param3 | Delay(s) | Cycle time (seconds, decimal) - time between each toggle. |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
Mission planner screenshots
In the example above, assuming the relay was off to begin with, it would be set high and then after 3 seconds, it would be toggled low again.
MAV_CMD_DO_SET_SERVO¶
Supported by: All vehicles.
Set a given servo pin output to a specific PWM value.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Ser No | Servo number - target servo output pin/channel number. |
param2 | PWM | PWM value to output, in microseconds (typically 1000 to 2000). |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
Mission planner screenshots
In the example above, the servo attached to output channel 8 would be moved to PWM 1700 (servos generally accept PWM values between 1000 and 2000).
Note
as of firmware versions 4.0 and later, this command can be used on any output configured by its SERVOx_FUNCTION
command as 0,1, or 51-66 (disabled or RC pass-throughs)
MAV_CMD_DO_REPEAT_SERVO¶
Supported by: All vehicles.
Cycle a servo PWM output pin between its mid-position value and a specified PWM value, for a given number of cycles and with a set period.
The mid-position value is specified in the RCn_TRIM
parameter for
the channel (RC8_TRIM
in the screenshot below). The default value is
1500..
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Ser No | Servo number - target servo output pin/channel. |
param2 | PWM | PWM value to output, in microseconds (typically 1000 to 2000). |
param3 | Repeat # | Cycle count - number of times to move the servo to the specified PWM value |
param4 | Delay (s) | Cycle time (seconds) - the delay in seconds between each servo movement. |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
Mission planner screenshots
In the example above, the servo attached to output channel 8 would be moved to PWM 1700, then after 4 second, back to mid, after another 4 seconds it would be moved to 1700 again, then finally after 4 more seconds it would be moved back to mid.
MAV_CMD_DO_LAND_START¶
Supported by: Plane (not Copter, Rover).
Mission command to prepare for a landing.
This is used as a marker in a mission to tell the autopilot where a
sequence of mission items that represents a landing starts. It may also
be sent via a COMMAND_LONG
to trigger a landing, in which case the
nearest (geographically) landing sequence in the mission will be used.
If RTL_AUTOLAND
is set to 2, the plane will jump to the nearest
DO_LAND_START
in the mission table when RTL is initialized.
Note
General information on landing a plane is provided in the topic Automatic Landing.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Empty | |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Lat | Latitude used to help find the closest landing sequence, or zero if not needed. |
param6 | Long | Longitude used to help find the closest landing sequence, or zero if not needed. |
param7 | Empty |
MAV_CMD_DO_VTOL_TRANSITION¶
Supported by: Plane (not Copter or Rover).Specifically QuadPlanes.
Mission command to change to/from VTOL and fixed wing mode of flight. The mode is changed based on the first parameter: 3 = change to VTOL flight, 4 = change to fixed wing flight.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Mode | 3=VTOL,4=Fixed-Wing |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_DO_SET_ROI¶
Supported by: Copter, Plane, Rover.
Points the camera gimbal at the “region of interest”.
After setting the ROI, the camera will continue to follow it until the
end of the mission, unless it is changed or cleared by setting another
ROI. Clearing the ROI is achieved by setting a later DO_SET_ROI
command with all zeros for param5
-param7
(Lat, Lon and Alt).
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Region of interest mode. (see MAV_ROI enum) // 0 = no roi, 1 = next waypoint, 2 = waypoint number, 3 = fixed location, 4 = given target (not supported) | |
param2 | MISSION index/ target ID. (see MAV_ROI enum) | |
param3 | ROI index (allows a vehicle to manage multiple ROI's) | |
param4 | Empty | |
param5 | Lat | Latitude (x) of the fixed ROI |
param6 | Long | Longitude (y) of the fixed ROI |
param7 | Alt | Altitude of the fixed ROI |
MAV_CMD_DO_DIGICAM_CONFIGURE¶
Supported by: All vehicles.
Configure an on-board camera controller system.
The parameters are forwarded to an on-board camera controller system (like the 3DR Camera Control Board), if one is present.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Mode | Set camera mode: 1: ProgramAuto 2: Aperture Priority 3: Shutter Priority 4: Manual 5: IntelligentAuto 6: SuperiorAuto |
param2 | Shutter Speed | Shutter speed (seconds divisor). So if the speed is 1/60 seconds, the value entered would be 60. Slowest shutter trigger supported is 1 second. |
param3 | Aperture | Aperture: F stop number |
param4 | ISO | ISO number e.g. 80, 100, 200, etc. |
param5 | ExposureMode | Exposure type enumerator |
param6 | CommandID | Command Identity |
param7 | Engine Cut-Off | Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off). |
MAV_CMD_DO_DIGICAM_CONTROL¶
Supported by: All vehicles.
Trigger the camera shutter once. This command takes no additional arguments.
Command parameters
In general, if a command field is set to 0 it is ignored.
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | On/Off | Session control (on/off or show/hide lens): 0: Turn off the camera / hide the lens 1: Turn on the camera /Show the lens |
param2 | Zoom Position | Zoom's absolute position. 2x, 3x, 10x, etc. |
param3 | Zoom Step | Zooming step value to offset zoom from the current position |
param4 | Focus Lock | Focus Locking, Unlocking or Re-locking: 0: Ignore 1: Unlock 2: Lock |
param5 | Shutter Cmd | Shooting Command. Any non-zero value triggers the camera. |
param6 | CommandID | Command Identity |
param7 | Empty |
Mission planner screenshots
MAV_CMD_DO_MOUNT_CONTROL¶
Supported by: All vehicles.
Mission command to control a camera or antenna mount.
This command allows you to specify a roll, pitch and yaw angle which will be sent to the camera gimbal. This can be used to point the camera in specific directions at various times in the mission.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Pitch, in degrees. | |
param2 | Roll, in degrees. | |
param3 | Yaw, in degrees. | |
param4 | reserved | |
param5 | reserved | |
param6 | reserved | |
param7 | `MAV_MOUNT_MODE |
Mission planner screenshots
MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW¶
Supported by: All vehicles.
Mission command to move the gimbal to the desired pitch and yaw angles (in degrees).
This command allows you to specify a pitch and yaw angle which will be sent to the camera gimbal. This can be used to point the camera in specific directions at various times in the mission. Positive pitch angles are up, Negative are down. Positive yaw angles are clockwise, negative are counter clockwise.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Pitch, in degrees. | |
param2 | Yaw, in degrees. | |
param3 | PitchRate, in deg/s. | |
param4 | YawRate, in deg/s | |
param5 | Flags: 0=boddyframe, 16=earthframe | |
param6 | reserved | |
param7 | Gimbal instance ID |
Mission planner screenshots
MAV_CMD_DO_SET_CAM_TRIGG_DIST¶
Supported by: All vehicles.
Trigger the camera shutter at regular distance intervals. This command is useful in camera survey missions. To trigger the camera once, immediately after passing the DO command, set param3 to 1. Trigger immediately Parameter is available from ArduPilot 4.1 onwards.
Note
Providing a distance of zero will stop the camera shutter from being triggered.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Dist (m) | Camera trigger distance interval (meters). Zero to turn off distance triggering. |
param2 | Empty | param3 | ? | Trigger once instantly. One is on, zero is off. |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
Mission planner screenshots
The above configuration will cause the camera shutter to trigger after every 5m that the vehicle travels.
MAV_CMD_DO_FENCE_ENABLE¶
Supported by: All vehicles.
Mission commands to enable the Plane GeoFence, Copter/Rover Cylindrical Fence and/or Inclusion and Exclusion Fences.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Set GeoFence enable state (0=disable, 1=enable, 2= disable only floor (Plane only)). | |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_DO_AUX_FUNCTION¶
Supported by: All vehicles.
Mission command to control an Auxiliary Function in the same manner as an RC channel switch.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | Aux Function | Auxiliary Function code,same as RCx_OPTIONS |
param2 | Switch Position | 0:Low, 1:Mid, 2:High |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_DO_INVERTED_FLIGHT¶
Supported by: Plane (not Copter or Rover).
Change between normal and inverted flight.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | 0=normal, 1=inverted | Set flight type: 0: normal 1: inverted |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_DO_AUTOTUNE_ENABLE¶
Supported by: Plane (not Copter or Rover).
Enable/disable AUTOTUNE mode.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | na | Enable/disable autotune (1: enable, 0:disable) |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_DO_ENGINE_CONTROL¶
Supported by: Plane (not Copter or Rover).
Stop or start the internal combustion engine (ICE)
This command can be used to start or stop the ICE before a NAV_VTOL_LAND or after a NAV_VTOL_TAKEOFF command for a QuadPlane to avoid potential prop strikes in the wind. It should be placed before either of those commands.Also can be used to allow a single engine start while disarmed if otherwise prohibited by ICE_OPTIONS bit 3 being set,
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | ? | Start/Stop ICE (1: start, 0:stop) | param2 | Cold Start (1: enables choke, currently not implemented) | param3 | Altitude in meters. Altitude at which action is taken. | param4 | Flags: 1 = allow a single start while disarmed even if :ref:`ICE_OPTIONS |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_DO_SET_RESUME_REPEAT_DIST¶
Supported by: All vehicles.
Set the distance that the mission will be rewound when resuming after an interrupt (switching modes). A full explanation of this feature can be found on the Mission Rewind on Resume Page. After setting a rewind distance in a mission, setting the distance to zero will switch off the rewind feature from that point on the mission.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | ? | Rewind distance in meters |
param2 | Empty | |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |
MAV_CMD_STORAGE_FORMAT¶
Supported by: All vehicles.
Format SD Card. Useful for vehicles where SD card is inaccessible. Param1 and Param2 must be set to 1.
Command parameters
Command Field | Mission Planner Field | Description |
---|---|---|
param1 | ? | Must be 1 |
param2 | ? | Must be 1 |
param3 | Empty | |
param4 | Empty | |
param5 | Empty | |
param6 | Empty | |
param7 | Empty |