Mavlink Command List

Table of contents

  • Table of contents

  • Version history

  • MAVLINK Messages

Set Camera Commands

Set Gimbal Commands

Get Payload Information

Version history

VersionPublish dateDescription

1.0.0

06 Jan 2023

Add example to do Connect payload Add example to do Load payload settings Add example to do Set payload settings Add example to do Image capture with the payload Add example to do Video record with the payload Add example to do Get video streaming from payload

1.0.1

25 May 2023

Included Gremsy gSDK to communicate and control gimbal Add examples to move gimbal in Angle mode and Angular rate mode using Mavlink Gimbal Protocol v2

v1.1.0

30 July 2024

Add some examples Get LRF status for VIO Payload define

v2.0.0

16 Aug 2024

Replace gSDK by MAVLINK interface Provide MAVLINK command list Publish resource

Encode a command_long structValuesDescription

target_system

1

target_component

191

MAV_COMP_ID_ONBOARD_COMPUTER

chan

0

MAVLink channel

Set camera running mode

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_SET_CAMERA_MODE (530)

MAV_CMD

confirmation

uint8_t

1

param2

float

0 1

Photo mode Video mode

Set camera record source

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_REC"

param_value

char[128]

"0" "1" "2" "5"

Record both Record EO Record IR Record OSD

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera view source

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_SOURCE"

param_value

char[128]

"0" "1" "2" "3" "4"

EO/IR Only EO Only IR IR/EO Sync

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set EO camera zoom mode

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_ZM_MODE"

param_value

char[128]

"0" "2"

Combine Super Resolution

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set EO camera zoom - Super Resolution

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_ZM_SR_LV"

param_value

char[128]

"0" "1" "2" "3" "4" "5" "6" "7" "8" "9" "10" "11" "12" "13" "14" "15"

1X 2X 4X 6X 8X 10X 12X 14X 16X 18X 20X 22X 24X 26X 28X 30X

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set EO camera index zoom - Combine

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_ZM_CB_LV"

param_value

char[128]

"0" "1" "2" "3" "4" "5" "6"

1X 10X 20X 40X 80X 120X 240X

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera zoom type

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_SET_CAMERA_ZOOM (531)

MAV_CMD

confirmation

uint8_t

1

param1

float

0 1 2

ZOOM_TYPE_STEP ZOOM_TYPE_CONTINUOUS ZOOM_TYPE_RANGE

param2

float

-1 for wide, 1 for tele -1 for wide, 1 for tele, 0 to stop zooming A percentage value between 0.0 and 100.0

Zoom one step increment Continuous zoom up/down until stopped Zoom value as proportion of full camera range

Set camera focus type

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_SET_CAMERA_FOCUS (532)

MAV_CMD

confirmation

uint8_t

1

param1

float

1 4

FOCUS_TYPE_CONTINUOUS FOCUS_TYPE_AUTO

param2

float

-1: focusing in, 1: focusing out, 0: stop

Continuous focus up/down until stopped

Set camera IR palette

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_T_PALETTE"

param_value

char[128]

"0" "1" "2" "3" "4" "5" "6" "7" "8" "9"

F1: WhiteHot ; G1: WhiteHot F1: BlackHot ; G1: Fulgurite F1: Rainbow ; G1: IronRed F1: RainbowHC ; G1: HotIron F1: Ironbow ; G1: Medical F1: Lava ; G1: Arctic F1: Arctic ; G1: Rainbow1 F1: Globow ; G1: Rainbow2 F1: Gradedfire ; G1: Tint F1: Hottest ; G1: BlackHot

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set payload camera start capture image

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_IMAGE_START_CAPTURE (2000)

MAV_CMD

confirmation

uint8_t

1

param2

int

Default, min: 0

Desired elapsed time between two consecutive pictures (in seconds)

Set payload camera stop capture image

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_IMAGE_STOP_CAPTURE (2001)

MAV_CMD

confirmation

uint8_t

1

Set payload camera start record video

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_VIDEO_START_CAPTURE (2500)

MAV_CMD

confirmation

uint8_t

1

Set payload camera stop record video

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD

MAV_CMD_VIDEO_STOP_CAPTURE (2501)

confirmation

uint8_t

1

Set camera video flip

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_FLIP"

param_value

char[128]

"2" "3"

On Off

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera video defog

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_DEFOG"

param_value

char[128]

"0" "1"

Off On

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera video defog level

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_DEFOG_LV"

param_value

char[128]

"0" "1" "2" "3"

Lowest Low Mid High

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera video auto exposure

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_AE"

param_value

char[128]

"0" "3" "10" "11" "13"

Auto Manual Shutter Iris Bright

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera video shutter speed

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_SP"

param_value

char[128]

"13" "14" "17" "20" "21" "25" "26" "27" "28" "30"

1/10 1/20 1/50 1/100 1/125 1/500 1/725 1/1000 1/1500 1/2000

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera video aperture value

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_IrP"

param_value

char[128]

0

Aperture value can be set from 0 to 25, step 1

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera video bright value

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_BrP"

param_value

char[128]

0

Bright value can be set from 0 to 41, step 1

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set camera video white balance

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"C_V_WB"

param_value

char[128]

"0" "1" "2" "3" "4" "5"

Auto Indoor Outdoor One push ATW Manual

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set gimbal mode

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"GB_MODE"

param_value

char[128]

"0" "1" "2" "3" "4"

OFF LOCK FOLLOW MAPPING RESET

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set gimbal RC mode

  • Message: PARAM_EXT_SET (323)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

param_id

char[16]

"RC_MODE"

param_value

char[128]

"0" "1"

Gremsy Standard

param_type

uint8_t

UINT32

MAV_PARAM_EXT_TYPE

Set gimbal move to angle

  • Message: GIMBAL_DEVICE_SET_ATTITUDE (284)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

q

float[4]

rad/s

mavlink_euler_to_quaternion(roll, pitch, yaw, q)

Quaternion components, w, x, y, z

angular_velocity_x

float

rad/s

NaN

X component of angular velocity (Roll)

angular_velocity_y

float

rad/s

NaN

Y component of angular velocity (Pitch)

angular_velocity_z

float

rad/s

NaN

Z component of angular velocity (Yaw)

Set gimbal move by speed

  • Message: GIMBAL_DEVICE_SET_ATTITUDE (284)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

q

float[4]

rad/s

NaN

Quaternion components, w, x, y, z

angular_velocity_x

float

rad/s

Speed roll

X component of angular velocity (Roll)

angular_velocity_y

float

rad/s

Speed pitch

Y component of angular velocity (Pitch)

angular_velocity_z

float

rad/s

Speed yaw

Z component of angular velocity (Yaw)

Get payload camera information

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_REQUEST_CAMERA_INFORMATION (521)

MAV_CMD

confirmation

uint8_t

1

Get payload camera streaming information

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION (2504)

MAV_CMD

confirmation

uint8_t

1

Get payload storage

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_REQUEST_STORAGE_INFORMATION (525)

MAV_CMD

confirmation

uint8_t

1

Get payload capture status

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (527)

MAV_CMD

confirmation

uint8_t

1

Get payload camera mode

  • Message: COMMAND_LONG (76)

Field NameTypeValuesDescription

target_system

uint8_t

1

System ID

target_component

uint8_t

101 (MAV_COMP_ID_CAMERA2)

MAVLINK Camera Component ID on Web setting

command

uint16_t

MAV_CMD_REQUEST_CAMERA_SETTINGS (522)

MAV_CMD

confirmation

uint8_t

1

Last updated