Enum mavlink::ualberta::MavCmd

source ·
pub enum MavCmd {
Show 159 variants MAV_CMD_NAV_WAYPOINT = 16, MAV_CMD_NAV_LOITER_UNLIM = 17, MAV_CMD_NAV_LOITER_TURNS = 18, MAV_CMD_NAV_LOITER_TIME = 19, MAV_CMD_NAV_RETURN_TO_LAUNCH = 20, MAV_CMD_NAV_LAND = 21, MAV_CMD_NAV_TAKEOFF = 22, MAV_CMD_NAV_LAND_LOCAL = 23, MAV_CMD_NAV_TAKEOFF_LOCAL = 24, MAV_CMD_NAV_FOLLOW = 25, MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30, MAV_CMD_NAV_LOITER_TO_ALT = 31, MAV_CMD_DO_FOLLOW = 32, MAV_CMD_DO_FOLLOW_REPOSITION = 33, MAV_CMD_DO_ORBIT = 34, MAV_CMD_NAV_ROI = 80, MAV_CMD_NAV_PATHPLANNING = 81, MAV_CMD_NAV_SPLINE_WAYPOINT = 82, MAV_CMD_NAV_VTOL_TAKEOFF = 84, MAV_CMD_NAV_VTOL_LAND = 85, MAV_CMD_NAV_GUIDED_ENABLE = 92, MAV_CMD_NAV_DELAY = 93, MAV_CMD_NAV_PAYLOAD_PLACE = 94, MAV_CMD_NAV_LAST = 95, MAV_CMD_CONDITION_DELAY = 112, MAV_CMD_CONDITION_CHANGE_ALT = 113, MAV_CMD_CONDITION_DISTANCE = 114, MAV_CMD_CONDITION_YAW = 115, MAV_CMD_CONDITION_LAST = 159, MAV_CMD_DO_SET_MODE = 176, MAV_CMD_DO_JUMP = 177, MAV_CMD_DO_CHANGE_SPEED = 178, MAV_CMD_DO_SET_HOME = 179, MAV_CMD_DO_SET_PARAMETER = 180, MAV_CMD_DO_SET_RELAY = 181, MAV_CMD_DO_REPEAT_RELAY = 182, MAV_CMD_DO_SET_SERVO = 183, MAV_CMD_DO_REPEAT_SERVO = 184, MAV_CMD_DO_FLIGHTTERMINATION = 185, MAV_CMD_DO_CHANGE_ALTITUDE = 186, MAV_CMD_DO_SET_ACTUATOR = 187, MAV_CMD_DO_LAND_START = 189, MAV_CMD_DO_RALLY_LAND = 190, MAV_CMD_DO_GO_AROUND = 191, MAV_CMD_DO_REPOSITION = 192, MAV_CMD_DO_PAUSE_CONTINUE = 193, MAV_CMD_DO_SET_REVERSE = 194, MAV_CMD_DO_SET_ROI_LOCATION = 195, MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196, MAV_CMD_DO_SET_ROI_NONE = 197, MAV_CMD_DO_SET_ROI_SYSID = 198, MAV_CMD_DO_CONTROL_VIDEO = 200, MAV_CMD_DO_SET_ROI = 201, MAV_CMD_DO_DIGICAM_CONFIGURE = 202, MAV_CMD_DO_DIGICAM_CONTROL = 203, MAV_CMD_DO_MOUNT_CONFIGURE = 204, MAV_CMD_DO_MOUNT_CONTROL = 205, MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206, MAV_CMD_DO_FENCE_ENABLE = 207, MAV_CMD_DO_PARACHUTE = 208, MAV_CMD_DO_MOTOR_TEST = 209, MAV_CMD_DO_INVERTED_FLIGHT = 210, MAV_CMD_DO_GRIPPER = 211, MAV_CMD_DO_AUTOTUNE_ENABLE = 212, MAV_CMD_NAV_SET_YAW_SPEED = 213, MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214, MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220, MAV_CMD_DO_GUIDED_MASTER = 221, MAV_CMD_DO_GUIDED_LIMITS = 222, MAV_CMD_DO_ENGINE_CONTROL = 223, MAV_CMD_DO_SET_MISSION_CURRENT = 224, MAV_CMD_DO_LAST = 240, MAV_CMD_PREFLIGHT_CALIBRATION = 241, MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242, MAV_CMD_PREFLIGHT_UAVCAN = 243, MAV_CMD_PREFLIGHT_STORAGE = 245, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246, MAV_CMD_OVERRIDE_GOTO = 252, MAV_CMD_OBLIQUE_SURVEY = 260, MAV_CMD_MISSION_START = 300, MAV_CMD_ACTUATOR_TEST = 310, MAV_CMD_CONFIGURE_ACTUATOR = 311, MAV_CMD_COMPONENT_ARM_DISARM = 400, MAV_CMD_RUN_PREARM_CHECKS = 401, MAV_CMD_ILLUMINATOR_ON_OFF = 405, MAV_CMD_GET_HOME_POSITION = 410, MAV_CMD_INJECT_FAILURE = 420, MAV_CMD_START_RX_PAIR = 500, MAV_CMD_GET_MESSAGE_INTERVAL = 510, MAV_CMD_SET_MESSAGE_INTERVAL = 511, MAV_CMD_REQUEST_MESSAGE = 512, MAV_CMD_REQUEST_PROTOCOL_VERSION = 519, MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520, MAV_CMD_REQUEST_CAMERA_INFORMATION = 521, MAV_CMD_REQUEST_CAMERA_SETTINGS = 522, MAV_CMD_REQUEST_STORAGE_INFORMATION = 525, MAV_CMD_STORAGE_FORMAT = 526, MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527, MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528, MAV_CMD_RESET_CAMERA_SETTINGS = 529, MAV_CMD_SET_CAMERA_MODE = 530, MAV_CMD_SET_CAMERA_ZOOM = 531, MAV_CMD_SET_CAMERA_FOCUS = 532, MAV_CMD_SET_STORAGE_USAGE = 533, MAV_CMD_JUMP_TAG = 600, MAV_CMD_DO_JUMP_TAG = 601, MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1_000, MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1_001, MAV_CMD_IMAGE_START_CAPTURE = 2_000, MAV_CMD_IMAGE_STOP_CAPTURE = 2_001, MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2_002, MAV_CMD_DO_TRIGGER_CONTROL = 2_003, MAV_CMD_CAMERA_TRACK_POINT = 2_004, MAV_CMD_CAMERA_TRACK_RECTANGLE = 2_005, MAV_CMD_CAMERA_STOP_TRACKING = 2_010, MAV_CMD_VIDEO_START_CAPTURE = 2_500, MAV_CMD_VIDEO_STOP_CAPTURE = 2_501, MAV_CMD_VIDEO_START_STREAMING = 2_502, MAV_CMD_VIDEO_STOP_STREAMING = 2_503, MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2_504, MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2_505, MAV_CMD_LOGGING_START = 2_510, MAV_CMD_LOGGING_STOP = 2_511, MAV_CMD_AIRFRAME_CONFIGURATION = 2_520, MAV_CMD_CONTROL_HIGH_LATENCY = 2_600, MAV_CMD_PANORAMA_CREATE = 2_800, MAV_CMD_DO_VTOL_TRANSITION = 3_000, MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3_001, MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4_000, MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4_001, MAV_CMD_CONDITION_GATE = 4_501, MAV_CMD_NAV_FENCE_RETURN_POINT = 5_000, MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5_001, MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5_002, MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5_003, MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5_004, MAV_CMD_NAV_RALLY_POINT = 5_100, MAV_CMD_UAVCAN_GET_NODE_INFO = 5_200, MAV_CMD_DO_ADSB_OUT_IDENT = 10_001, MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30_001, MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30_002, MAV_CMD_FIXED_MAG_CAL_YAW = 42_006, MAV_CMD_DO_WINCH = 42_600, MAV_CMD_WAYPOINT_USER_1 = 31_000, MAV_CMD_WAYPOINT_USER_2 = 31_001, MAV_CMD_WAYPOINT_USER_3 = 31_002, MAV_CMD_WAYPOINT_USER_4 = 31_003, MAV_CMD_WAYPOINT_USER_5 = 31_004, MAV_CMD_SPATIAL_USER_1 = 31_005, MAV_CMD_SPATIAL_USER_2 = 31_006, MAV_CMD_SPATIAL_USER_3 = 31_007, MAV_CMD_SPATIAL_USER_4 = 31_008, MAV_CMD_SPATIAL_USER_5 = 31_009, MAV_CMD_USER_1 = 31_010, MAV_CMD_USER_2 = 31_011, MAV_CMD_USER_3 = 31_012, MAV_CMD_USER_4 = 31_013, MAV_CMD_USER_5 = 31_014, MAV_CMD_CAN_FORWARD = 32_000,
}
Expand description

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§

§

MAV_CMD_NAV_WAYPOINT = 16

Navigate to waypoint.

§

MAV_CMD_NAV_LOITER_UNLIM = 17

Loiter around this waypoint an unlimited amount of time

§

MAV_CMD_NAV_LOITER_TURNS = 18

Loiter around this waypoint for X turns

§

MAV_CMD_NAV_LOITER_TIME = 19

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.

§

MAV_CMD_NAV_RETURN_TO_LAUNCH = 20

Return to launch location

§

MAV_CMD_NAV_LAND = 21

Land at location.

§

MAV_CMD_NAV_TAKEOFF = 22

Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode.

§

MAV_CMD_NAV_LAND_LOCAL = 23

Land at local position (local frame only)

§

MAV_CMD_NAV_TAKEOFF_LOCAL = 24

Takeoff from local position (local frame only)

§

MAV_CMD_NAV_FOLLOW = 25

Vehicle following, i.e. this waypoint represents the position of a moving vehicle

§

MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30

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.

§

MAV_CMD_NAV_LOITER_TO_ALT = 31

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.

§

MAV_CMD_DO_FOLLOW = 32

Begin following a target

§

MAV_CMD_DO_FOLLOW_REPOSITION = 33

Reposition the MAV after a follow target command has been sent

§

MAV_CMD_DO_ORBIT = 34

Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults.

§

MAV_CMD_NAV_ROI = 80

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.

§

MAV_CMD_NAV_PATHPLANNING = 81

Control autonomous path planning on the MAV.

§

MAV_CMD_NAV_SPLINE_WAYPOINT = 82

Navigate to waypoint using a spline path.

§

MAV_CMD_NAV_VTOL_TAKEOFF = 84

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

§

MAV_CMD_NAV_VTOL_LAND = 85

Land using VTOL mode

§

MAV_CMD_NAV_GUIDED_ENABLE = 92

hand control over to an external controller

§

MAV_CMD_NAV_DELAY = 93

Delay the next navigation command a number of seconds or until a specified time

§

MAV_CMD_NAV_PAYLOAD_PLACE = 94

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.

§

MAV_CMD_NAV_LAST = 95

NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration

§

MAV_CMD_CONDITION_DELAY = 112

Delay mission state machine.

§

MAV_CMD_CONDITION_CHANGE_ALT = 113

Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached.

§

MAV_CMD_CONDITION_DISTANCE = 114

Delay mission state machine until within desired distance of next NAV point.

§

MAV_CMD_CONDITION_YAW = 115

Reach a certain target angle.

§

MAV_CMD_CONDITION_LAST = 159

NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration

§

MAV_CMD_DO_SET_MODE = 176

Set system mode.

§

MAV_CMD_DO_JUMP = 177

Jump to the desired command in the mission list. Repeat this action only the specified number of times

§

MAV_CMD_DO_CHANGE_SPEED = 178

Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change.

§

MAV_CMD_DO_SET_HOME = 179

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

§

MAV_CMD_DO_SET_PARAMETER = 180

Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.

§

MAV_CMD_DO_SET_RELAY = 181

Set a relay to a condition.

§

MAV_CMD_DO_REPEAT_RELAY = 182

Cycle a relay on and off for a desired number of cycles with a desired period.

§

MAV_CMD_DO_SET_SERVO = 183

Set a servo to a desired PWM value.

§

MAV_CMD_DO_REPEAT_SERVO = 184

Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.

§

MAV_CMD_DO_FLIGHTTERMINATION = 185

Terminate flight immediately. Flight termination immediately and irreversably 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.

§

MAV_CMD_DO_CHANGE_ALTITUDE = 186

Change altitude set point.

§

MAV_CMD_DO_SET_ACTUATOR = 187

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

§

MAV_CMD_DO_LAND_START = 189

Mission command to perform 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. The Latitude/Longitude/Altitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence.

§

MAV_CMD_DO_RALLY_LAND = 190

Mission command to perform a landing from a rally point.

§

MAV_CMD_DO_GO_AROUND = 191

Mission command to safely abort an autonomous landing.

§

MAV_CMD_DO_REPOSITION = 192

Reposition the vehicle to a specific WGS84 global position.

§

MAV_CMD_DO_PAUSE_CONTINUE = 193

If in a GPS controlled position mode, hold the current position or continue.

§

MAV_CMD_DO_SET_REVERSE = 194

Set moving direction to forward or reverse.

§

MAV_CMD_DO_SET_ROI_LOCATION = 195

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.

§

MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196

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.

§

MAV_CMD_DO_SET_ROI_NONE = 197

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.

§

MAV_CMD_DO_SET_ROI_SYSID = 198

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.

§

MAV_CMD_DO_CONTROL_VIDEO = 200

Control onboard camera system.

§

MAV_CMD_DO_SET_ROI = 201

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.

§

MAV_CMD_DO_DIGICAM_CONFIGURE = 202

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

§

MAV_CMD_DO_DIGICAM_CONTROL = 203

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

§

MAV_CMD_DO_MOUNT_CONFIGURE = 204

Mission command to configure a camera or antenna mount

§

MAV_CMD_DO_MOUNT_CONTROL = 205

Mission command to control a camera or antenna mount

§

MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206

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.

§

MAV_CMD_DO_FENCE_ENABLE = 207

Mission command to enable the geofence

§

MAV_CMD_DO_PARACHUTE = 208

Mission item/command to release a parachute or enable/disable auto release.

§

MAV_CMD_DO_MOTOR_TEST = 209

Command to perform motor test.

§

MAV_CMD_DO_INVERTED_FLIGHT = 210

Change to/from inverted flight.

§

MAV_CMD_DO_GRIPPER = 211

Mission command to operate a gripper.

§

MAV_CMD_DO_AUTOTUNE_ENABLE = 212

Enable/disable autotune.

§

MAV_CMD_NAV_SET_YAW_SPEED = 213

Sets a desired vehicle turn angle and speed change.

§

MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214

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.

§

MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220

Mission command to control a camera or antenna mount, using a quaternion as reference.

§

MAV_CMD_DO_GUIDED_MASTER = 221

set id of master controller

§

MAV_CMD_DO_GUIDED_LIMITS = 222

Set limits for external control

§

MAV_CMD_DO_ENGINE_CONTROL = 223

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

§

MAV_CMD_DO_SET_MISSION_CURRENT = 224

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 command may 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. Resetting sets 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).

§

MAV_CMD_DO_LAST = 240

NOP - This command is only used to mark the upper limit of the DO commands in the enumeration

§

MAV_CMD_PREFLIGHT_CALIBRATION = 241

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.

§

MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242

Set sensor offsets. This command will be only accepted if in pre-flight mode.

§

MAV_CMD_PREFLIGHT_UAVCAN = 243

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

§

MAV_CMD_PREFLIGHT_STORAGE = 245

Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.

§

MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246

Request the reboot or shutdown of system components.

§

MAV_CMD_OVERRIDE_GOTO = 252

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.

§

MAV_CMD_OBLIQUE_SURVEY = 260

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.

§

MAV_CMD_MISSION_START = 300

start running a mission

§

MAV_CMD_ACTUATOR_TEST = 310

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 typically refuse this command while armed.

§

MAV_CMD_CONFIGURE_ACTUATOR = 311

Actuator configuration command.

§

MAV_CMD_COMPONENT_ARM_DISARM = 400

Arms / Disarms a component

§

MAV_CMD_RUN_PREARM_CHECKS = 401

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.

§

MAV_CMD_ILLUMINATOR_ON_OFF = 405

Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light).

§

MAV_CMD_GET_HOME_POSITION = 410

Request the home position from the vehicle. The vehicle will ACK the command and then emit the HOME_POSITION message.

§

MAV_CMD_INJECT_FAILURE = 420

Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting.

§

MAV_CMD_START_RX_PAIR = 500

Starts receiver pairing.

§

MAV_CMD_GET_MESSAGE_INTERVAL = 510

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.

§

MAV_CMD_SET_MESSAGE_INTERVAL = 511

Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM.

§

MAV_CMD_REQUEST_MESSAGE = 512

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

§

MAV_CMD_REQUEST_PROTOCOL_VERSION = 519

Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message

§

MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520

Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message

§

MAV_CMD_REQUEST_CAMERA_INFORMATION = 521

Request camera information (CAMERA_INFORMATION).

§

MAV_CMD_REQUEST_CAMERA_SETTINGS = 522

Request camera settings (CAMERA_SETTINGS).

§

MAV_CMD_REQUEST_STORAGE_INFORMATION = 525

Request storage information (STORAGE_INFORMATION). Use the command’s target_component to target a specific component’s storage.

§

MAV_CMD_STORAGE_FORMAT = 526

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.

§

MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527

Request camera capture status (CAMERA_CAPTURE_STATUS)

§

MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528

Request flight information (FLIGHT_INFORMATION)

§

MAV_CMD_RESET_CAMERA_SETTINGS = 529

Reset all camera settings to Factory Default

§

MAV_CMD_SET_CAMERA_MODE = 530

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.

§

MAV_CMD_SET_CAMERA_ZOOM = 531

Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success).

§

MAV_CMD_SET_CAMERA_FOCUS = 532

Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success).

§

MAV_CMD_SET_STORAGE_USAGE = 533

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.

§

MAV_CMD_JUMP_TAG = 600

Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG.

§

MAV_CMD_DO_JUMP_TAG = 601

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.

§

MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1_000

High level setpoint to be sent to a gimbal manager to set a gimbal attitude. 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: a gimbal is never to react to this command but only the gimbal manager.

§

MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1_001

Gimbal configuration to set which sysid/compid is in primary and secondary control.

§

MAV_CMD_IMAGE_START_CAPTURE = 2_000

Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values.

§

MAV_CMD_IMAGE_STOP_CAPTURE = 2_001

Stop image capture sequence Use NaN for reserved values.

§

MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2_002

Re-request a CAMERA_IMAGE_CAPTURED message.

§

MAV_CMD_DO_TRIGGER_CONTROL = 2_003

Enable or disable on-board camera triggering system.

§

MAV_CMD_CAMERA_TRACK_POINT = 2_004

If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking.

§

MAV_CMD_CAMERA_TRACK_RECTANGLE = 2_005

If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking.

§

MAV_CMD_CAMERA_STOP_TRACKING = 2_010

Stops ongoing tracking.

§

MAV_CMD_VIDEO_START_CAPTURE = 2_500

Starts video capture (recording).

§

MAV_CMD_VIDEO_STOP_CAPTURE = 2_501

Stop the current video capture (recording).

§

MAV_CMD_VIDEO_START_STREAMING = 2_502

Start video streaming

§

MAV_CMD_VIDEO_STOP_STREAMING = 2_503

Stop the given video stream

§

MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2_504

Request video stream information (VIDEO_STREAM_INFORMATION)

§

MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2_505

Request video stream status (VIDEO_STREAM_STATUS)

§

MAV_CMD_LOGGING_START = 2_510

Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)

§

MAV_CMD_LOGGING_STOP = 2_511

Request to stop streaming log data over MAVLink

§

MAV_CMD_AIRFRAME_CONFIGURATION = 2_520

§

MAV_CMD_CONTROL_HIGH_LATENCY = 2_600

Request to start/stop transmitting over the high latency telemetry

§

MAV_CMD_PANORAMA_CREATE = 2_800

Create a panorama at the current position

§

MAV_CMD_DO_VTOL_TRANSITION = 3_000

Request VTOL transition

§

MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3_001

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.

§

MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4_000

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.

§

MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4_001

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.

§

MAV_CMD_CONDITION_GATE = 4_501

Delay mission state machine until gate has been reached.

§

MAV_CMD_NAV_FENCE_RETURN_POINT = 5_000

Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead.

§

MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5_001

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.

§

MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5_002

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.

§

MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5_003

Circular fence area. The vehicle must stay inside this area.

§

MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5_004

Circular fence area. The vehicle must stay outside this area.

§

MAV_CMD_NAV_RALLY_POINT = 5_100

Rally point. You can have multiple rally points defined.

§

MAV_CMD_UAVCAN_GET_NODE_INFO = 5_200

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.

§

MAV_CMD_DO_ADSB_OUT_IDENT = 10_001

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.

§

MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30_001

Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.

§

MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30_002

Control the payload deployment.

§

MAV_CMD_FIXED_MAG_CAL_YAW = 42_006

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.

§

MAV_CMD_DO_WINCH = 42_600

Command to operate winch.

§

MAV_CMD_WAYPOINT_USER_1 = 31_000

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

§

MAV_CMD_WAYPOINT_USER_2 = 31_001

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

§

MAV_CMD_WAYPOINT_USER_3 = 31_002

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

§

MAV_CMD_WAYPOINT_USER_4 = 31_003

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

§

MAV_CMD_WAYPOINT_USER_5 = 31_004

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

§

MAV_CMD_SPATIAL_USER_1 = 31_005

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

§

MAV_CMD_SPATIAL_USER_2 = 31_006

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

§

MAV_CMD_SPATIAL_USER_3 = 31_007

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

§

MAV_CMD_SPATIAL_USER_4 = 31_008

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

§

MAV_CMD_SPATIAL_USER_5 = 31_009

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

§

MAV_CMD_USER_1 = 31_010

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

§

MAV_CMD_USER_2 = 31_011

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

§

MAV_CMD_USER_3 = 31_012

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

§

MAV_CMD_USER_4 = 31_013

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

§

MAV_CMD_USER_5 = 31_014

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

§

MAV_CMD_CAN_FORWARD = 32_000

Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages

Implementations§

source§

impl MavCmd

source

pub const DEFAULT: Self = Self::MAV_CMD_NAV_WAYPOINT

Trait Implementations§

source§

impl Clone for MavCmd

source§

fn clone(&self) -> MavCmd

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl Debug for MavCmd

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
source§

impl Default for MavCmd

source§

fn default() -> Self

Returns the “default value” for a type. Read more
source§

impl<'de> Deserialize<'de> for MavCmd

source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
source§

impl FromPrimitive for MavCmd

source§

fn from_i64(n: i64) -> Option<Self>

Converts an i64 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_u64(n: u64) -> Option<Self>

Converts an u64 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_isize(n: isize) -> Option<Self>

Converts an isize to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_i8(n: i8) -> Option<Self>

Converts an i8 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_i16(n: i16) -> Option<Self>

Converts an i16 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_i32(n: i32) -> Option<Self>

Converts an i32 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_i128(n: i128) -> Option<Self>

Converts an i128 to return an optional value of this type. If the value cannot be represented by this type, then None is returned. Read more
source§

fn from_usize(n: usize) -> Option<Self>

Converts a usize to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_u8(n: u8) -> Option<Self>

Converts an u8 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_u16(n: u16) -> Option<Self>

Converts an u16 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_u32(n: u32) -> Option<Self>

Converts an u32 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_u128(n: u128) -> Option<Self>

Converts an u128 to return an optional value of this type. If the value cannot be represented by this type, then None is returned. Read more
source§

fn from_f32(n: f32) -> Option<Self>

Converts a f32 to return an optional value of this type. If the value cannot be represented by this type, then None is returned.
source§

fn from_f64(n: f64) -> Option<Self>

Converts a f64 to return an optional value of this type. If the value cannot be represented by this type, then None is returned. Read more
source§

impl PartialEq for MavCmd

source§

fn eq(&self, other: &MavCmd) -> bool

This method tests for self and other values to be equal, and is used by ==.
1.0.0 · source§

fn ne(&self, other: &Rhs) -> bool

This method tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl Serialize for MavCmd

source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
source§

impl ToPrimitive for MavCmd

source§

fn to_i64(&self) -> Option<i64>

Converts the value of self to an i64. If the value cannot be represented by an i64, then None is returned.
source§

fn to_u64(&self) -> Option<u64>

Converts the value of self to a u64. If the value cannot be represented by a u64, then None is returned.
source§

fn to_isize(&self) -> Option<isize>

Converts the value of self to an isize. If the value cannot be represented by an isize, then None is returned.
source§

fn to_i8(&self) -> Option<i8>

Converts the value of self to an i8. If the value cannot be represented by an i8, then None is returned.
source§

fn to_i16(&self) -> Option<i16>

Converts the value of self to an i16. If the value cannot be represented by an i16, then None is returned.
source§

fn to_i32(&self) -> Option<i32>

Converts the value of self to an i32. If the value cannot be represented by an i32, then None is returned.
source§

fn to_i128(&self) -> Option<i128>

Converts the value of self to an i128. If the value cannot be represented by an i128 (i64 under the default implementation), then None is returned. Read more
source§

fn to_usize(&self) -> Option<usize>

Converts the value of self to a usize. If the value cannot be represented by a usize, then None is returned.
source§

fn to_u8(&self) -> Option<u8>

Converts the value of self to a u8. If the value cannot be represented by a u8, then None is returned.
source§

fn to_u16(&self) -> Option<u16>

Converts the value of self to a u16. If the value cannot be represented by a u16, then None is returned.
source§

fn to_u32(&self) -> Option<u32>

Converts the value of self to a u32. If the value cannot be represented by a u32, then None is returned.
source§

fn to_u128(&self) -> Option<u128>

Converts the value of self to a u128. If the value cannot be represented by a u128 (u64 under the default implementation), then None is returned. Read more
source§

fn to_f32(&self) -> Option<f32>

Converts the value of self to an f32. Overflows may map to positive or negative inifinity, otherwise None is returned if the value cannot be represented by an f32.
source§

fn to_f64(&self) -> Option<f64>

Converts the value of self to an f64. Overflows may map to positive or negative inifinity, otherwise None is returned if the value cannot be represented by an f64. Read more
source§

impl Copy for MavCmd

source§

impl StructuralPartialEq for MavCmd

Auto Trait Implementations§

Blanket Implementations§

source§

impl<T> Any for Twhere T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for Twhere T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for Twhere T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T, U> Into<U> for Twhere U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

source§

impl<T> ToOwned for Twhere T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
source§

impl<T, U> TryFrom<U> for Twhere U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for Twhere U: TryFrom<T>,

§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<T> DeserializeOwned for Twhere T: for<'de> Deserialize<'de>,