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.
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.
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.
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 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).
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.
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.
This command can be used to start a mission when the Copter is on the
ground in AUTO mode. If the vehicle is already in the air then the
mission will start as soon as you switch into AUTO mode (so this command
is not needed/ignored).
Note
Previously a mission would only start after the pilot engaged the
throttle. This command makes it possible to start missions without
directly controlling the throttle (though that approach is still
available).
This is not a “mission command” (it can’t be used as a type of mission
waypoint). It is run from the Action menu (see the screenshot
below).
Command parameters
The parameters are all ignored.
Command Field
Mission Planner Field
Description
param1
The first mission item to run.
param2
The last mission item to run (after this item is run, the mission ends).
Navigation commands are used to control the movement of the vehicle,
including takeoff, moving to and around waypoints, and landing.
NAV commands have the highest priority. Any DO_ and CONDITION_
commands that have not executed when a NAV command is loaded are skipped
(for example, if a waypoint completes and the NAV command for another
waypoint is loaded, and unexecuted DO/CONDITION commands associated with
the first waypoint are dropped.
The Copter will fly a straight line to the specified latitude, longitude
and altitude. It will then wait at the point for a specified delay time
and then proceed to the next waypoint.
Command parameters
Command Field
Mission Planner Field
Description
param1
Delay
Hold time at mission waypoint in decimal seconds - MAX 65535 seconds. (Copter/Rover only)
param2
Acceptance radius in meters (when plain inside the sphere of this radius, the waypoint is considered reached) (Plane only).
param3
0 to pass through the WP, if > 0 radius in meters to pass by WP.
Positive value for clockwise orbit, negative value for counter-clockwise
orbit. Allows trajectory control.
param4
Desired yaw angle at waypoint target.(rotary wing)
param5
Lat
Target latitude. If zero, the Copter will hold at the current latitude.
param6
Lon
Target longitude. If zero, the Copter will hold at the current longitude.
param7
Alt
Target altitude. If zero, the Copter will hold at the current altitude.
Parameters 2-4 are not supported on Copter:
Hit Rad - is supposed to hold the distance (in meters) from the
target point that will qualify the waypoint as complete. This command
is not supported. Instead the
WPNAV_RADIUS
parameter should be used (see “WP Radius” field in screen shot or
adjust through the Standard Parameters List). Even the WPNAV_RADIUS
is only used when the waypoint has a Delay. With no delay specified
the waypoint will be considered complete when the virtual point that
the vehicle is chasing reaches the waypoint. This can be 10m (or
more) ahead of the vehicle meaning that the vehicle will turn towards
the following waypoint long before it actually reaches the current
waypoint
Yaw Ang - is supposed to hold the resulting yaw angle in degrees
(0=north, 90 = east). Instead use a
MAV_CMD_CONDITION_YAW command.
The vehicle will climb straight up from it’s current location to the
specified altitude. If the mission is begun while the copter is already
flying, the vehicle will climb straight up to the specified altitude, if
the vehicle is already above the altitude the command will be ignored
and the mission will move onto the next command immediately.
Fly to the specified location and then loiter there indefinitely — where
loiter means “wait in place” (rather than “circle”). If zero is
specified for a latitude/longitude/altitude parameter then the current
location value for the parameter will be used.
The mission will not proceed past this command while in AUTO mode. In
order to break out of this command you need to change the mode (i.e. to
MANUAL). If there are subsequent commands then you can continue the
mission at the next command, if the Copter MIS_RESTART parameter is
set to resume, by switching back to AUTO mode (otherwise the mission
will restart).
Command parameters
Command Field
Mission Planner Field
Description
param1
Empty
param2
Empty
param3
Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise
param4
Desired yaw angle.
param5
Lat
Target latitude. If zero, the vehicle will loiter at the current latitude.
param6
Lon
Target longitude. If zero, the vehicle will loiter at the current longitude.
param7
Alt
Target altitude. If zero, the vehicle will loiter at the current altitude.
Loiter (circle) the specified location for a specified number of turns,
and then proceed to the next command. If zero is specified for a
latitude/longitude/altitude parameter then the current location value
for the parameter will be used.
The radius of the circle is controlled by the
CIRCLE_RADIUS
parameter (i.e. cannot be set as part of the command).
Fly to the specified location and then loiter there for the specified
number of seconds — where loiter means “wait in place” (rather than
“circle”). The timer starts when the waypoint is reached; when it
expires the waypoint is complete. If zero is specified for a
latitude/longitude/altitude parameter then the current location value
for the parameter will be used.
Return to the home location or the nearest Rally
Point, if closer. The home location is where
the vehicle was last armed (or when it first gets GPS lock after arming
if the vehicle configuration allows this).
#HW TODO / Questions - Randy: Check that copter still uses RTL_ALT
parameter and doesn’t try to send information about height in the
package.
Return to the home location (or the nearest Rally Point if closer) and then land. The home
location is where the vehicle was last armed (or when it first gets GPS
lock after arming if the vehicle configuration allows this).
This is the mission equivalent of the RTL flight mode. The vehicle will
first climb to the
RTL_ALT
parameter’s specified altitude (default is 15m) before returning home.
This command takes no parameters and generally should be the last
command in the mission.
Command parameters
Command Field
Mission Planner Field
Description
param1
Empty
param2
Empty
param3
Empty
param4
Empty
param5
Empty
param6
Empty
param7
Empty
Mission planner screenshots
Copter: Mission PlannerSettings for RETURN_TO_LAUNCH command
The copter will land at it’s current location or at the lat/lon
coordinates provided (if non-zero). This is the mission equivalent of
the LAND flight mode.
The motors will not stop on their own: you must exit AUTO mode to cut
the engines.
#HW TODO / Questions - LAND in the “Creating a mission with waypoints
doc” states : “If you have Sonar, the craft will stop holding position
at 3 meters and drop straight down.” Is that true, and what does it
mean?
Command parameters
Command Field
Mission Planner Field
Description
param1
Empty
param2
Empty
param3
Empty
param4
Desired yaw angle.
param5
Lat
Target latitude. If zero, the Copter will land at the current latitude.
Fly to the target location using a Spline path, then
wait (hover) for specified time before proceeding to the next command.
The Spline commands take all the same arguments are regular waypoints
(lat, lon, alt, delay) but when executed the vehicle will fly smooth
paths (both vertically and horizontally) instead of straight lines.
Spline waypoints can be mixed with regular straight line waypoints as
shown in the screenshot below.
Enable GUIDED mode to hand over control to an external controller. See Guided Mode
for more information.
#HW TODO: Questions - Randy - How is this command actually “used” ? Ie
when you’ve turned on guided mode, does this mean you can then just send
up individual mission commands ? ie from a DroneKit point of view, how
do you use this.
Command parameters
Command Field
Mission Planner Field
Description
param1
on=1/off=0
A value of > 0.5 enables GUIDED mode. Any value <= 0.5f turns it off.
Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then
loiter at the current position. Don’t consider the navigation command
complete (don’t leave loiter) until the altitude has been reached.
Additionally, if the Heading Required parameter is non-zero the aircraft
will not leave the loiter until heading toward the next waypoint.
Jump to the specified command in the mission list. The jump command can
be repeated either a specified number of times before continuing the
mission, or it can be repeated indefinitely.
Tip
Despite the name, this command is really a “NAV_” command rather
than a “DO_” command. Conditional commands like CONDITION_DELAY don’t
affect DO_JUMP (it will always perform the jump as soon as it reaches
the command).
Note
This command can be called a maximum number of 15 times in a mission,
after which new DO_JUMP commands are ignored. The maximum number
changed from 3 to 15 in AC 3.3.
The command was introduced in/works reliably from AC3.2
Command parameters
Command Field
Mission Planner Field
Description
param1
WP#
The command index/sequence number of the command to jump to.
param2
Repeat#
Number of times that the DO_JUMP command will execute before moving to
the next sequential command. If the value is zero the next command will
execute immediately. A value of -1 will cause the command to repeat
indefinitely.
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.
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.
Point (yaw) the nose of the vehicle towards a specified heading.
The parameters allow you to specify whether the target direction is
absolute or relative to the current yaw direction. If the direction is
relative you can also (separately) specify whether the value is added or
subtracted from the current heading (note that the vehicle will always
turn in direction that most quickly gets it to the new target heading
regardless of the param3 value).
We don’t support controlling the yaw rate, so the param2 value (Sec)
is ignored.
Command parameters
Command Field
Mission Planner Field
Description
param1
Deg
If param4=0 (absolute): Target heading in degrees [0-360] (0 is North).
If param4=1 (relative): The change in heading (in degrees).
param2
Sec
Speed during yaw change:[deg per second].
param3
Dir 1=CW
If param4=1 (relative) only: [-1 = CCW, +1 = CW]. This denotes
whether the flight controller should add (CW) or subtract (CCW) the
degrees (``param1``) from the current heading to calculate the target heading.
param4
rel/abs
Specify if param1 ("Deg" field) is an absolute direction (0) or a relative to the current yaw direction (1).
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.
Sets the desired maximum speed in meters/second (only). Both the
speed-type and throttle settings are ignored.
Note
In AC3.1.5 (and earlier) versions the speed change will only take
effect after the current navigation command (i.e. waypoint command)
completes. From AC3.2 onwards the vehicle speed will change
immediately.
Command parameters
Command Field
Mission Planner Field
Description
param1
speed m/s
Speed type (0=Airspeed, 1=Ground Speed).
param2
speed m/s
Target speed (m/s).
param3
Throttle as a percentage (0-100%). A value of -1 indicates no change.
From AC3.2 the speed parameter will be in the SECOND COLUMN, not
the first column as in previous releases and shown above (this is to
match the official MAVLINK protocol)
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.
Warning
This command should not be used in AC3.2 due to this issue. Instead
Rally Points can be used to control the
position used for RETURN_TO_LAUNCH (“Home” is also used internally as
the “origin” for all navigation calculations). The command is fixed in
AC3.3.
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.
#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
Copter: MissionPlanner Settings for DO_SET_RELAY 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.
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.
Points the camera gimbal at the “region
of interest”, and also rotates the nose of the vehicle if the
mount type does not support a yaw feature.
After setting the ROI, the camera/vehicle 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 zero for param5-param7 (Lat, Lon
and Alt).
The above behaviour was implemented in AC3.2. In AC3.1.5 the
camera/vehicle only tracks the ROI in the waypoint it is declared. A new
ROI therefore needs to be set at every waypoint where tracking is
required.
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)
In the example above the nose and camera would be pointed at the red
marker.
If using AC3.1.5: The nose would point at the marker for only the period
that the vehicle is flying from Waypoint #1 to Waypoint #3. If you
wanted the nose/camera to continue to point at the red marker as it
flies from #3 to #4, a second DO_SET_ROI command would need to be
entered after Waypoint #3.
If using AC3.2: The nose would continue to point at the red marker until
the end of the mission. To “clear” the do-set-roi and cause the vehicle
to return to it’s default behaviour (i.e. pointing at the next waypoint)
a second DO_SET_ROI command should be placed later in the mission with
all zero for Lat, Lon and Alt.
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
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
Copter: Mission PlannerSettings for DO_MOUNT_CONTROL command
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
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.
This command sets time, altitude, and distance limits for external
control (GUIDED mode). When these limits are exceeded, control will
return from GUIDED mode to the mission. Setting any of these parameters
to zero will remove the associated limit.
Command parameters
Command Field
Mission Planner Field
Description
param1
timeout S
Maximum time (in seconds) that the external controller is allowed to
control vehicle. Use 0 to remove time limits (unlimited time allowed).
param2
min alt
Minimum allowed absolute altitude (in meters, AMSL), below which the
command will be aborted and the mission will continue. Use 0 to indicate
that there is no minimum altitude limit.
param3
max alt
Maximum allowed absolute altitude (in meters, AMSL), above which the
command will be aborted and the mission will continue. Use 0 to indicate
that there is no maximum altitude limit.
param4
max dist
Horizontal move limit (in meters, AMSL). If vehicle moves more than this
distance from its location at the moment the command was executed, the
command will be aborted and the mission will continue. Use 0 to indicate
that there is no horizontal limit.