#[repr(u16)]pub enum MavCmd {
Show 165 variants
NavWaypoint = 16,
NavLoiterUnlim = 17,
NavLoiterTurns = 18,
NavLoiterTime = 19,
NavReturnToLaunch = 20,
NavLand = 21,
NavTakeoff = 22,
NavLandLocal = 23,
NavTakeoffLocal = 24,
NavFollow = 25,
NavContinueAndChangeAlt = 30,
NavLoiterToAlt = 31,
DoFollow = 32,
DoFollowReposition = 33,
DoOrbit = 34,
NavRoi = 80,
NavPathplanning = 81,
NavSplineWaypoint = 82,
NavVtolTakeoff = 84,
NavVtolLand = 85,
NavGuidedEnable = 92,
NavDelay = 93,
NavPayloadPlace = 94,
NavLast = 95,
ConditionDelay = 112,
ConditionChangeAlt = 113,
ConditionDistance = 114,
ConditionYaw = 115,
ConditionLast = 159,
DoSetMode = 176,
DoJump = 177,
DoChangeSpeed = 178,
DoSetHome = 179,
DoSetParameter = 180,
DoSetRelay = 181,
DoRepeatRelay = 182,
DoSetServo = 183,
DoRepeatServo = 184,
DoFlighttermination = 185,
DoChangeAltitude = 186,
DoSetActuator = 187,
DoReturnPathStart = 188,
DoLandStart = 189,
DoRallyLand = 190,
DoGoAround = 191,
DoReposition = 192,
DoPauseContinue = 193,
DoSetReverse = 194,
DoSetRoiLocation = 195,
DoSetRoiWpnextOffset = 196,
DoSetRoiNone = 197,
DoSetRoiSysid = 198,
DoControlVideo = 200,
DoSetRoi = 201,
DoDigicamConfigure = 202,
DoDigicamControl = 203,
DoMountConfigure = 204,
DoMountControl = 205,
DoSetCamTriggDist = 206,
DoFenceEnable = 207,
DoParachute = 208,
DoMotorTest = 209,
DoInvertedFlight = 210,
DoGripper = 211,
DoAutotuneEnable = 212,
NavSetYawSpeed = 213,
DoSetCamTriggInterval = 214,
DoMountControlQuat = 220,
DoGuidedMaster = 221,
DoGuidedLimits = 222,
DoEngineControl = 223,
DoSetMissionCurrent = 224,
DoLast = 240,
PreflightCalibration = 241,
PreflightSetSensorOffsets = 242,
PreflightUavcan = 243,
PreflightStorage = 245,
PreflightRebootShutdown = 246,
OverrideGoto = 252,
ObliqueSurvey = 260,
DoSetStandardMode = 262,
MissionStart = 300,
ActuatorTest = 310,
ConfigureActuator = 311,
ComponentArmDisarm = 400,
RunPrearmChecks = 401,
IlluminatorOnOff = 405,
DoIlluminatorConfigure = 406,
GetHomePosition = 410,
InjectFailure = 420,
StartRxPair = 500,
GetMessageInterval = 510,
SetMessageInterval = 511,
RequestMessage = 512,
RequestProtocolVersion = 519,
RequestAutopilotCapabilities = 520,
RequestCameraInformation = 521,
RequestCameraSettings = 522,
RequestStorageInformation = 525,
StorageFormat = 526,
RequestCameraCaptureStatus = 527,
RequestFlightInformation = 528,
ResetCameraSettings = 529,
SetCameraMode = 530,
SetCameraZoom = 531,
SetCameraFocus = 532,
SetStorageUsage = 533,
SetCameraSource = 534,
JumpTag = 600,
DoJumpTag = 601,
DoGimbalManagerPitchyaw = 1_000,
DoGimbalManagerConfigure = 1_001,
ImageStartCapture = 2_000,
ImageStopCapture = 2_001,
RequestCameraImageCapture = 2_002,
DoTriggerControl = 2_003,
CameraTrackPoint = 2_004,
CameraTrackRectangle = 2_005,
CameraStopTracking = 2_010,
VideoStartCapture = 2_500,
VideoStopCapture = 2_501,
VideoStartStreaming = 2_502,
VideoStopStreaming = 2_503,
RequestVideoStreamInformation = 2_504,
RequestVideoStreamStatus = 2_505,
LoggingStart = 2_510,
LoggingStop = 2_511,
AirframeConfiguration = 2_520,
ControlHighLatency = 2_600,
PanoramaCreate = 2_800,
DoVtolTransition = 3_000,
ArmAuthorizationRequest = 3_001,
SetGuidedSubmodeStandard = 4_000,
SetGuidedSubmodeCircle = 4_001,
ConditionGate = 4_501,
NavFenceReturnPoint = 5_000,
NavFencePolygonVertexInclusion = 5_001,
NavFencePolygonVertexExclusion = 5_002,
NavFenceCircleInclusion = 5_003,
NavFenceCircleExclusion = 5_004,
NavRallyPoint = 5_100,
UavcanGetNodeInfo = 5_200,
DoSetSafetySwitchState = 5_300,
DoAdsbOutIdent = 10_001,
PayloadPrepareDeploy = 30_001,
PayloadControlDeploy = 30_002,
WaypointUser1 = 31_000,
WaypointUser2 = 31_001,
WaypointUser3 = 31_002,
WaypointUser4 = 31_003,
WaypointUser5 = 31_004,
SpatialUser1 = 31_005,
SpatialUser2 = 31_006,
SpatialUser3 = 31_007,
SpatialUser4 = 31_008,
SpatialUser5 = 31_009,
User1 = 31_010,
User2 = 31_011,
User3 = 31_012,
User4 = 31_013,
User5 = 31_014,
CanForward = 32_000,
FixedMagCalYaw = 42_006,
DoWinch = 42_600,
ExternalPositionEstimate = 43_003,
}Expand description
MAVLink enum MAV_CMD for common dialect.
Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component’s current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries
Variants§
MAVLink enum entry MAV_CMD_NAV_WAYPOINT.
Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION).
MAVLink enum entry MAV_CMD_NAV_LOITER_UNLIM.
Loiter around this waypoint an unlimited amount of time
MAVLink enum entry MAV_CMD_NAV_LOITER_TURNS.
Loiter around this waypoint for X turns
MAVLink enum entry MAV_CMD_NAV_LOITER_TIME.
Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint.
MAVLink enum entry MAV_CMD_NAV_RETURN_TO_LAUNCH.
Return to launch location
MAVLink enum entry MAV_CMD_NAV_LAND.
Land at location.
MAVLink enum entry MAV_CMD_NAV_TAKEOFF.
Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode.
MAVLink enum entry MAV_CMD_NAV_LAND_LOCAL.
Land at local position (local frame only)
MAVLink enum entry MAV_CMD_NAV_TAKEOFF_LOCAL.
Takeoff from local position (local frame only)
MAVLink enum entry MAV_CMD_NAV_FOLLOW.
Vehicle following, i.e. this waypoint represents the position of a moving vehicle
MAVLink enum entry MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT.
Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don’t proceed to the next command until the desired altitude is reached.
MAVLink enum entry MAV_CMD_NAV_LOITER_TO_ALT.
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.
DoFollow = 32
MAVLink enum entry MAV_CMD_DO_FOLLOW.
Begin following a target
DoFollowReposition = 33
MAVLink enum entry MAV_CMD_DO_FOLLOW_REPOSITION.
Reposition the MAV after a follow target command has been sent
DoOrbit = 34
MAVLink enum entry MAV_CMD_DO_ORBIT.
Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults.
MAVLink enum entry MAV_CMD_NAV_ROI.
Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle’s control system to control the vehicle attitude and the attitude of various sensors such as cameras.
MAVLink enum entry MAV_CMD_NAV_PATHPLANNING.
Control autonomous path planning on the MAV.
MAVLink enum entry MAV_CMD_NAV_SPLINE_WAYPOINT.
Navigate to waypoint using a spline path.
MAVLink enum entry MAV_CMD_NAV_VTOL_TAKEOFF.
Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.).
MAVLink enum entry MAV_CMD_NAV_VTOL_LAND.
Land using VTOL mode
MAVLink enum entry MAV_CMD_NAV_GUIDED_ENABLE.
hand control over to an external controller
MAVLink enum entry MAV_CMD_NAV_DELAY.
Delay the next navigation command a number of seconds or until a specified time
MAVLink enum entry MAV_CMD_NAV_PAYLOAD_PLACE.
Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload.
MAVLink enum entry MAV_CMD_NAV_LAST.
NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration
ConditionDelay = 112
MAVLink enum entry MAV_CMD_CONDITION_DELAY.
Delay mission state machine.
ConditionChangeAlt = 113
MAVLink enum entry MAV_CMD_CONDITION_CHANGE_ALT.
Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached.
ConditionDistance = 114
MAVLink enum entry MAV_CMD_CONDITION_DISTANCE.
Delay mission state machine until within desired distance of next NAV point.
ConditionYaw = 115
MAVLink enum entry MAV_CMD_CONDITION_YAW.
Reach a certain target angle.
ConditionLast = 159
MAVLink enum entry MAV_CMD_CONDITION_LAST.
NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration
DoSetMode = 176
MAVLink enum entry MAV_CMD_DO_SET_MODE.
Set system mode.
DoJump = 177
MAVLink enum entry MAV_CMD_DO_JUMP.
Jump to the desired command in the mission list. Repeat this action only the specified number of times
DoChangeSpeed = 178
MAVLink enum entry MAV_CMD_DO_CHANGE_SPEED.
Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change
DoSetHome = 179
MAVLink enum entry MAV_CMD_DO_SET_HOME.
Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).
DoSetParameter = 180
MAVLink enum entry MAV_CMD_DO_SET_PARAMETER.
Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.
DoSetRelay = 181
MAVLink enum entry MAV_CMD_DO_SET_RELAY.
Set a relay to a condition.
DoRepeatRelay = 182
MAVLink enum entry MAV_CMD_DO_REPEAT_RELAY.
Cycle a relay on and off for a desired number of cycles with a desired period.
DoSetServo = 183
MAVLink enum entry MAV_CMD_DO_SET_SERVO.
Set a servo to a desired PWM value.
DoRepeatServo = 184
MAVLink enum entry MAV_CMD_DO_REPEAT_SERVO.
Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.
DoFlighttermination = 185
MAVLink enum entry MAV_CMD_DO_FLIGHTTERMINATION.
Terminate flight immediately. Flight termination immediately and irreversibly terminates the current flight, returning the vehicle to ground. The vehicle will ignore RC or other input until it has been power-cycled. Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing). On multicopters without a parachute it may trigger a crash landing. Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION. Support for this command can also be tested by sending the command with param1=0 (< 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED.
DoChangeAltitude = 186
MAVLink enum entry MAV_CMD_DO_CHANGE_ALTITUDE.
Change altitude set point.
DoSetActuator = 187
MAVLink enum entry MAV_CMD_DO_SET_ACTUATOR.
Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter).
DoReturnPathStart = 188
MAVLink enum entry MAV_CMD_DO_RETURN_PATH_START.
Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item). A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint). The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path. The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path. If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing. If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing. The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed. If specified, the item defines the waypoint at which the return segment starts. If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored.
DoLandStart = 189
MAVLink enum entry MAV_CMD_DO_LAND_START.
Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern.
When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern. It should be followed by a navigation item that defines the first waypoint of the landing sequence. The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded). If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence.
When sent as a command it triggers a landing using a mission landing pattern. The location parameters are not used in this case, and should be set to 0.
DoRallyLand = 190
MAVLink enum entry MAV_CMD_DO_RALLY_LAND.
Mission command to perform a landing from a rally point.
DoGoAround = 191
MAVLink enum entry MAV_CMD_DO_GO_AROUND.
Mission command to safely abort an autonomous landing.
DoReposition = 192
MAVLink enum entry MAV_CMD_DO_REPOSITION.
Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead).
DoPauseContinue = 193
MAVLink enum entry MAV_CMD_DO_PAUSE_CONTINUE.
If in a GPS controlled position mode, hold the current position or continue.
DoSetReverse = 194
MAVLink enum entry MAV_CMD_DO_SET_REVERSE.
Set moving direction to forward or reverse.
DoSetRoiLocation = 195
MAVLink enum entry MAV_CMD_DO_SET_ROI_LOCATION.
Sets the region of interest (ROI) to a location. This can then be used by the vehicle’s control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message.
DoSetRoiWpnextOffset = 196
MAVLink enum entry MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET.
Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle’s control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message.
DoSetRoiNone = 197
MAVLink enum entry MAV_CMD_DO_SET_ROI_NONE.
Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle’s control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position.
DoSetRoiSysid = 198
MAVLink enum entry MAV_CMD_DO_SET_ROI_SYSID.
Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message.
DoControlVideo = 200
MAVLink enum entry MAV_CMD_DO_CONTROL_VIDEO.
Control onboard camera system.
DoSetRoi = 201
MAVLink enum entry MAV_CMD_DO_SET_ROI.
Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle’s control system to control the vehicle attitude and the attitude of various sensors such as cameras.
DoDigicamConfigure = 202
MAVLink enum entry MAV_CMD_DO_DIGICAM_CONFIGURE.
Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ).
DoDigicamControl = 203
MAVLink enum entry MAV_CMD_DO_DIGICAM_CONTROL.
Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ).
DoMountConfigure = 204
MAVLink enum entry MAV_CMD_DO_MOUNT_CONFIGURE.
Mission command to configure a camera or antenna mount
DoMountControl = 205
MAVLink enum entry MAV_CMD_DO_MOUNT_CONTROL.
Mission command to control a camera or antenna mount
DoSetCamTriggDist = 206
MAVLink enum entry MAV_CMD_DO_SET_CAM_TRIGG_DIST.
Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera.
DoFenceEnable = 207
MAVLink enum entry MAV_CMD_DO_FENCE_ENABLE.
Enable the geofence. This can be used in a mission or via the command protocol. The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot.
DoParachute = 208
MAVLink enum entry MAV_CMD_DO_PARACHUTE.
Mission item/command to release a parachute or enable/disable auto release.
DoMotorTest = 209
MAVLink enum entry MAV_CMD_DO_MOTOR_TEST.
Command to perform motor test.
DoInvertedFlight = 210
MAVLink enum entry MAV_CMD_DO_INVERTED_FLIGHT.
Change to/from inverted flight.
DoGripper = 211
MAVLink enum entry MAV_CMD_DO_GRIPPER.
Mission command to operate a gripper.
DoAutotuneEnable = 212
MAVLink enum entry MAV_CMD_DO_AUTOTUNE_ENABLE.
Enable/disable autotune.
MAVLink enum entry MAV_CMD_NAV_SET_YAW_SPEED.
Sets a desired vehicle turn angle and speed change.
DoSetCamTriggInterval = 214
MAVLink enum entry MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL.
Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera.
DoMountControlQuat = 220
MAVLink enum entry MAV_CMD_DO_MOUNT_CONTROL_QUAT.
Mission command to control a camera or antenna mount, using a quaternion as reference.
DoGuidedMaster = 221
MAVLink enum entry MAV_CMD_DO_GUIDED_MASTER.
set id of master controller
DoGuidedLimits = 222
MAVLink enum entry MAV_CMD_DO_GUIDED_LIMITS.
Set limits for external control
DoEngineControl = 223
MAVLink enum entry MAV_CMD_DO_ENGINE_CONTROL.
Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines
DoSetMissionCurrent = 224
MAVLink enum entry MAV_CMD_DO_SET_MISSION_CURRENT.
Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2).
This commandmay trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode.
The mission may be "reset" using param2.
Resettingsets jump counters to initial values (to reset counters without changing the current
mission item set the param1 to -1).
Resetting also explicitly changes a mission
state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE,
potentially allowing it to resume when it is (next) in a mission mode.
The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item).
DoLast = 240
MAVLink enum entry MAV_CMD_DO_LAST.
NOP - This command is only used to mark the upper limit of the DO commands in the enumeration
PreflightCalibration = 241
MAVLink enum entry MAV_CMD_PREFLIGHT_CALIBRATION.
Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero.
PreflightSetSensorOffsets = 242
MAVLink enum entry MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS.
Set sensor offsets. This command will be only accepted if in pre-flight mode.
PreflightUavcan = 243
MAVLink enum entry MAV_CMD_PREFLIGHT_UAVCAN.
Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named).
PreflightStorage = 245
MAVLink enum entry MAV_CMD_PREFLIGHT_STORAGE.
Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.
PreflightRebootShutdown = 246
MAVLink enum entry MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN.
Request the reboot or shutdown of system components.
OverrideGoto = 252
MAVLink enum entry MAV_CMD_OVERRIDE_GOTO.
Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position.
ObliqueSurvey = 260
MAVLink enum entry MAV_CMD_OBLIQUE_SURVEY.
Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera.
DoSetStandardMode = 262
MAVLink enum entry MAV_CMD_DO_SET_STANDARD_MODE.
Enable the specified standard MAVLink mode. If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. See https://mavlink.io/en/services/standard_modes.html
MissionStart = 300
MAVLink enum entry MAV_CMD_MISSION_START.
start running a mission
ActuatorTest = 310
MAVLink enum entry MAV_CMD_ACTUATOR_TEST.
Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed.
ConfigureActuator = 311
MAVLink enum entry MAV_CMD_CONFIGURE_ACTUATOR.
Actuator configuration command.
ComponentArmDisarm = 400
MAVLink enum entry MAV_CMD_COMPONENT_ARM_DISARM.
Arms / Disarms a component
RunPrearmChecks = 401
MAVLink enum entry MAV_CMD_RUN_PREARM_CHECKS.
Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed.
IlluminatorOnOff = 405
MAVLink enum entry MAV_CMD_ILLUMINATOR_ON_OFF.
Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light).
DoIlluminatorConfigure = 406
MAVLink enum entry MAV_CMD_DO_ILLUMINATOR_CONFIGURE.
Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light).
GetHomePosition = 410
MAVLink enum entry MAV_CMD_GET_HOME_POSITION.
Request the home position from the vehicle. The vehicle will ACK the command and then emit the HOME_POSITION message.
InjectFailure = 420
MAVLink enum entry MAV_CMD_INJECT_FAILURE.
Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting.
StartRxPair = 500
MAVLink enum entry MAV_CMD_START_RX_PAIR.
Starts receiver pairing.
GetMessageInterval = 510
MAVLink enum entry MAV_CMD_GET_MESSAGE_INTERVAL.
Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message.
SetMessageInterval = 511
MAVLink enum entry MAV_CMD_SET_MESSAGE_INTERVAL.
Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM.
RequestMessage = 512
MAVLink enum entry MAV_CMD_REQUEST_MESSAGE.
Request the target system(s) emit a single instance of a specified message (i.e. a “one-shot” version of MAV_CMD_SET_MESSAGE_INTERVAL).
RequestProtocolVersion = 519
MAVLink enum entry MAV_CMD_REQUEST_PROTOCOL_VERSION.
Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message
RequestAutopilotCapabilities = 520
MAVLink enum entry MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES.
Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message
RequestCameraInformation = 521
MAVLink enum entry MAV_CMD_REQUEST_CAMERA_INFORMATION.
Request camera information (CAMERA_INFORMATION).
RequestCameraSettings = 522
MAVLink enum entry MAV_CMD_REQUEST_CAMERA_SETTINGS.
Request camera settings (CAMERA_SETTINGS).
RequestStorageInformation = 525
MAVLink enum entry MAV_CMD_REQUEST_STORAGE_INFORMATION.
Request storage information (STORAGE_INFORMATION). Use the command’s target_component to target a specific component’s storage.
StorageFormat = 526
MAVLink enum entry MAV_CMD_STORAGE_FORMAT.
Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command’s target_component to target a specific component’s storage.
RequestCameraCaptureStatus = 527
MAVLink enum entry MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS.
Request camera capture status (CAMERA_CAPTURE_STATUS)
RequestFlightInformation = 528
MAVLink enum entry MAV_CMD_REQUEST_FLIGHT_INFORMATION.
Request flight information (FLIGHT_INFORMATION)
ResetCameraSettings = 529
MAVLink enum entry MAV_CMD_RESET_CAMERA_SETTINGS.
Reset all camera settings to Factory Default
SetCameraMode = 530
MAVLink enum entry MAV_CMD_SET_CAMERA_MODE.
Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming.
SetCameraZoom = 531
MAVLink enum entry MAV_CMD_SET_CAMERA_ZOOM.
Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success).
SetCameraFocus = 532
MAVLink enum entry MAV_CMD_SET_CAMERA_FOCUS.
Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success).
SetStorageUsage = 533
MAVLink enum entry MAV_CMD_SET_STORAGE_USAGE.
Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED.
SetCameraSource = 534
MAVLink enum entry MAV_CMD_SET_CAMERA_SOURCE.
Set camera source. Changes the camera’s active sources on cameras with multiple image sensors.
JumpTag = 600
MAVLink enum entry MAV_CMD_JUMP_TAG.
Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG.
DoJumpTag = 601
MAVLink enum entry MAV_CMD_DO_JUMP_TAG.
Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number.
DoGimbalManagerPitchyaw = 1_000
MAVLink enum entry MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW.
Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate.
DoGimbalManagerConfigure = 1_001
MAVLink enum entry MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE.
Gimbal configuration to set which sysid/compid is in primary and secondary control.
ImageStartCapture = 2_000
MAVLink enum entry MAV_CMD_IMAGE_START_CAPTURE.
Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture.
Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions.
When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command’s target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both.
When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.
ImageStopCapture = 2_001
MAVLink enum entry MAV_CMD_IMAGE_STOP_CAPTURE.
Stop image capture sequence.
Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions.
When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command’s target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both.
When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.
RequestCameraImageCapture = 2_002
MAVLink enum entry MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE.
Re-request a CAMERA_IMAGE_CAPTURED message.
DoTriggerControl = 2_003
MAVLink enum entry MAV_CMD_DO_TRIGGER_CONTROL.
Enable or disable on-board camera triggering system.
CameraTrackPoint = 2_004
MAVLink enum entry MAV_CMD_CAMERA_TRACK_POINT.
If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking.
CameraTrackRectangle = 2_005
MAVLink enum entry MAV_CMD_CAMERA_TRACK_RECTANGLE.
If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking.
CameraStopTracking = 2_010
MAVLink enum entry MAV_CMD_CAMERA_STOP_TRACKING.
Stops ongoing tracking.
VideoStartCapture = 2_500
MAVLink enum entry MAV_CMD_VIDEO_START_CAPTURE.
Starts video capture (recording).
VideoStopCapture = 2_501
MAVLink enum entry MAV_CMD_VIDEO_STOP_CAPTURE.
Stop the current video capture (recording).
VideoStartStreaming = 2_502
MAVLink enum entry MAV_CMD_VIDEO_START_STREAMING.
Start video streaming
VideoStopStreaming = 2_503
MAVLink enum entry MAV_CMD_VIDEO_STOP_STREAMING.
Stop the given video stream
RequestVideoStreamInformation = 2_504
MAVLink enum entry MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION.
Request video stream information (VIDEO_STREAM_INFORMATION)
RequestVideoStreamStatus = 2_505
MAVLink enum entry MAV_CMD_REQUEST_VIDEO_STREAM_STATUS.
Request video stream status (VIDEO_STREAM_STATUS)
LoggingStart = 2_510
MAVLink enum entry MAV_CMD_LOGGING_START.
Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)
LoggingStop = 2_511
MAVLink enum entry MAV_CMD_LOGGING_STOP.
Request to stop streaming log data over MAVLink
AirframeConfiguration = 2_520
MAVLink enum entry MAV_CMD_AIRFRAME_CONFIGURATION.
ControlHighLatency = 2_600
MAVLink enum entry MAV_CMD_CONTROL_HIGH_LATENCY.
Request to start/stop transmitting over the high latency telemetry
PanoramaCreate = 2_800
MAVLink enum entry MAV_CMD_PANORAMA_CREATE.
Create a panorama at the current position
DoVtolTransition = 3_000
MAVLink enum entry MAV_CMD_DO_VTOL_TRANSITION.
Request VTOL transition
ArmAuthorizationRequest = 3_001
MAVLink enum entry MAV_CMD_ARM_AUTHORIZATION_REQUEST.
Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. If approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. If the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON.
SetGuidedSubmodeStandard = 4_000
MAVLink enum entry MAV_CMD_SET_GUIDED_SUBMODE_STANDARD.
This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes.
SetGuidedSubmodeCircle = 4_001
MAVLink enum entry MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE.
This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position.
ConditionGate = 4_501
MAVLink enum entry MAV_CMD_CONDITION_GATE.
Delay mission state machine until gate has been reached.
MAVLink enum entry MAV_CMD_NAV_FENCE_RETURN_POINT.
Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead.
MAVLink enum entry MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION.
Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon.
MAVLink enum entry MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION.
Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon.
MAVLink enum entry MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION.
Circular fence area. The vehicle must stay inside this area.
MAVLink enum entry MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION.
Circular fence area. The vehicle must stay outside this area.
MAVLink enum entry MAV_CMD_NAV_RALLY_POINT.
Rally point. You can have multiple rally points defined.
UavcanGetNodeInfo = 5_200
MAVLink enum entry MAV_CMD_UAVCAN_GET_NODE_INFO.
Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages.
DoSetSafetySwitchState = 5_300
MAVLink enum entry MAV_CMD_DO_SET_SAFETY_SWITCH_STATE.
Change state of safety switch.
DoAdsbOutIdent = 10_001
MAVLink enum entry MAV_CMD_DO_ADSB_OUT_IDENT.
Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec.
PayloadPrepareDeploy = 30_001
MAVLink enum entry MAV_CMD_PAYLOAD_PREPARE_DEPLOY.
Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.
PayloadControlDeploy = 30_002
MAVLink enum entry MAV_CMD_PAYLOAD_CONTROL_DEPLOY.
Control the payload deployment.
WaypointUser1 = 31_000
MAVLink enum entry MAV_CMD_WAYPOINT_USER_1.
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
WaypointUser2 = 31_001
MAVLink enum entry MAV_CMD_WAYPOINT_USER_2.
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
WaypointUser3 = 31_002
MAVLink enum entry MAV_CMD_WAYPOINT_USER_3.
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
WaypointUser4 = 31_003
MAVLink enum entry MAV_CMD_WAYPOINT_USER_4.
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
WaypointUser5 = 31_004
MAVLink enum entry MAV_CMD_WAYPOINT_USER_5.
User defined waypoint item. Ground Station will show the Vehicle as flying through this item.
SpatialUser1 = 31_005
MAVLink enum entry MAV_CMD_SPATIAL_USER_1.
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
SpatialUser2 = 31_006
MAVLink enum entry MAV_CMD_SPATIAL_USER_2.
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
SpatialUser3 = 31_007
MAVLink enum entry MAV_CMD_SPATIAL_USER_3.
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
SpatialUser4 = 31_008
MAVLink enum entry MAV_CMD_SPATIAL_USER_4.
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
SpatialUser5 = 31_009
MAVLink enum entry MAV_CMD_SPATIAL_USER_5.
User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.
User1 = 31_010
MAVLink enum entry MAV_CMD_USER_1.
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
User2 = 31_011
MAVLink enum entry MAV_CMD_USER_2.
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
User3 = 31_012
MAVLink enum entry MAV_CMD_USER_3.
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
User4 = 31_013
MAVLink enum entry MAV_CMD_USER_4.
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
User5 = 31_014
MAVLink enum entry MAV_CMD_USER_5.
User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.
CanForward = 32_000
MAVLink enum entry MAV_CMD_CAN_FORWARD.
Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages
FixedMagCalYaw = 42_006
MAVLink enum entry MAV_CMD_FIXED_MAG_CAL_YAW.
Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location.
DoWinch = 42_600
MAVLink enum entry MAV_CMD_DO_WINCH.
Command to operate winch.
ExternalPositionEstimate = 43_003
MAVLink enum entry MAV_CMD_EXTERNAL_POSITION_ESTIMATE.
Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link.
Implementations§
Trait Implementations§
Source§impl<'de> Deserialize<'de> for MavCmd
impl<'de> Deserialize<'de> for MavCmd
Source§fn deserialize<__D>(
__deserializer: __D,
) -> Result<MavCmd, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(
__deserializer: __D,
) -> Result<MavCmd, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
Source§impl NamedType for MavCmd
impl NamedType for MavCmd
fn sid() -> SpectaID
Source§fn named_data_type(
type_map: &mut TypeCollection,
generics: &[DataType],
) -> NamedDataType
fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType
Source§fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
Source§impl Serialize for MavCmd
impl Serialize for MavCmd
Source§fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
Source§impl Type for MavCmd
impl Type for MavCmd
Source§fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
Source§fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
definition will be put into the type map.