Mission Commands

This article describes the mission commands that are supported by Copter, Plane and Rover when switched into Auto mode.

Warning

This is a work-in-progress and has not been full reviewed. A better list 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 that 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 prioritise 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 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 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 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 gives 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 commands 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.

Conditional commands

Conditional commands control the execution of _DO_ commands. For example, a conditional command can prevent DO commands 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 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: Copter, Plane, Rover.

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

../_images/MissionList_ConditionDelay.png

Copter: Mission Planner Settingsfor CONDITION_DELAY command

In the example above, Command #4 (DO_SET_ROI) is delayed so that it starts 5 seconds after the vehicle has passed Waypoint #2.

Command parameters

Command Field Mission Planner Field Description
param1 Rate (cm/sec) Descent / Ascend rate (m/s).
param2 Empty
param3 Empty
param4 Empty
param5 Empty
param6 Empty
param7 Alt Target altitude

MAV_CMD_CONDITION_DISTANCE

Supported by: Copter, Plane, Rover.

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

../_images/MissionList_ConditionDistance.png

Copter: Mission PlannerSettings for CONDITION_DISTANCE command

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.

MAV_CMD_CONDITION_YAW

Supported by: Copter (not Plane or Rover).

Point (yaw) the nose of the vehicle towards a specified heading.

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_SET_MODE

Supported by: Copter, Plane, Rover.

Set system mode (preflight, armed, disarmed etc.)

Command parameters

Command Field Mission Planner Field Description
param1 Mode, as defined by `MAV_MODE `__
param2 Custom mode - this is system specific, please refer to the individual autopilot specifications for details.
param3 Empty
param4 Empty
param5 Empty
param6 Empty
param7 Empty

MAV_CMD_DO_CHANGE_SPEED

Supported by: Copter, Plane, Rover.

Change the target horizontal speed and/or throttle of the vehicle. The changes will be used until they are explicitly changed again or the device is rebooted.

MAV_CMD_DO_SET_HOME

Supported by: Copter, Plane, Rover.

Sets the home location either as the current location or at the location specified in the command.

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. 2=Use location specified in message parameters.
param2 Empty
param3 Empty
param4 Empty
param5 Lat Target home latitude (if ``param1=2``)
param6 Lon Target home longitude (if ``param1=2``)
param7 Alt Target home altitude (if ``param1=2``)

Mission planner screenshots

../_images/MissionList_DoSetHome.png

Copter: Mission Planner Settings forDO_SET_HOME command

MAV_CMD_DO_SET_RELAY

Supported by: Copter, Plane, Rover.

Set a Relay pin’s voltage high (on) or low (off).

#HW TODO / Question - is “toggling supported” using -1 in the setting? Some docs indicate this, but no information. “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 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)
param3 Empty
param4 Empty
param5 Empty
param6 Empty
param7 Empty

Mission planner screenshots

../_images/MissionPlanner_DO_SET_RELAY.png

Copter: MissionPlanner Settings for DO_SET_RELAY command

MAV_CMD_DO_REPEAT_RELAY

Supported by: Copter, Plane, Rover.

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

../_images/MissionList_DoRepeatRelay.png

Copter: Mission Planner Settingsfor DO_RELAY_REPEAT command

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: Copter, Plane, Rover.

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

../_images/MissionList_DoSetServo.png

Copter: Mission Planner Settingsfor DO_SET_SERVO command

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).

MAV_CMD_DO_REPEAT_SERVO

Supported by: Copter, Plane, Rover.

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

../_images/MissionList_DoRepeatServo.png

Copter: Mission Planner Settingsfor DO_REPEAT_SERVO command

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.

MAV_CMD_DO_SET_ROI

Supported by: Copter, Plane, Rover.

Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.

#HW TODO / Questions - What is the frame - altitude above home or above terrain or relative to vehicle?

#HW TODO / Questions - Is behaviour on all vehicles the same (except for Yaw). If so, merge 3 sections below.

MAV_CMD_DO_DIGICAM_CONFIGURE

Supported by: Copter, Plane, Rover.

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: Copter, Plane, Rover.

AC3.3: Control an on-board camera controller system (like the 3DR Camera Control Board).

Currently/BEFORE AC3.3: Trigger the camera shutter once. This command takes no additional arguments.

Command parameters

The parameters below reflect the supported fields in AC3.3. In general if a command field is sent as 0 it is ignored. All parameters are ignored prior to AC3.3.

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

../_images/MissionList_DoDigicamControl.png

Copter: Mission PlannerSettings for DO_DIGICAM_CONTROL command.

MAV_CMD_DO_MOUNT_CONTROL

Supported by: Copter, Plane, Rover.

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.

Note

Supported from AC3.3, Plane 3.4

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 `__ enum value.

Mission planner screenshots

../_images/MissionList_DoMountControl.png

Copter: Mission PlannerSettings for DO_MOUNT_CONTROL command

MAV_CMD_DO_SET_CAM_TRIGG_DIST

Supported by: Copter, Plane, Rover.

Trigger the camera shutter at regular distance intervals. This command is useful in camera survey missions.

Note

In AC3.1.5 (and earlier) versions this command cannot be shut-off. The camera will continue to be triggered repeatedly even after the mission has been ended. In AC3.2 (and higher) 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 Empty
param4 Empty
param5 Empty
param6 Empty
param7 Empty

Mission planner screenshots

../_images/MissionList_DoSetCamTriggDist.png

Copter: Mission PlannerSettings for DO_SET_CAM_TRIGG_DIST command

The above configuration above will cause the camera shutter to trigger after every 5m that the vehicle travels.

MAV_CMD_DO_FENCE_ENABLE

Supported by: Plane (not Copter or Rover).

Mission command to enable the GeoFence.

MAV_CMD_DO_PARACHUTE

Supported by: Copter (not Plane or Rover).

Mission command to trigger a parachute (if enabled).

MAV_CMD_DO_INVERTED_FLIGHT

Supported by: Plane (not Copter or Rover).

Change to/from inverted flight.

MAV_CMD_DO_GRIPPER

Supported by: Copter (not Plane or Rover).

Mission command to operate EPM gripper.

MAV_CMD_DO_GUIDED_LIMITS

Supported by: Copter (not Plane or Rover).

Set limits for external control.

MAV_CMD_DO_AUTOTUNE_ENABLE

Supported by: Plane (not Copter or Rover).

Enable/disable autotune.