Control a Gimbal / Camera Mount

This page explains how MAVLink can be used to control a gimbal (aka camera mount). In particular this page describes how to

  • use MAV_CMD_DO_MOUNT_CONTROL to set the gimbal’s mode (aka mount mode)

  • use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW to move to a desired angle or at a desired rate

  • use MAV_CMD_DO_SET_ROI_LOCATION to point at a Location

  • use MAV_CMD_DO_SET_ROI_NONE to stop point at a Location or vehicle

  • use MAV_CMD_DO_SET_ROI_SYSID to point at another vehicle

  • use MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE to take control of the gimbal (optional)

The gimbal’s attitude (in body-frame Quaternion form) can be monitored by decoding the GIMBAL_DEVICE_ATTITUDE_STATUS message.

Note

ArduPilot’s MAVLink interface for controlling gimbals was significantly upgraded for 4.3 compared with earlier versions. This page primarily discusses the interface for 4.3 (and higher) which aims to comply with the MAVLink Gimbalv2 protocol

Set the mode with MAV_CMD_DO_MOUNT_CONTROL

The gimbal/mount’s mode can be set by sending a COMMAND_LONG with the command and param7 fields set as specified for the MAV_CMD_DO_MOUNT_CONTROL command. The supported modes are:

  1. Retract : gimbal will move to a retracted position (see MNT1_RETRACT_X, Y, Z) or relax

  2. Neutral : gimbal will move to a neutral position (see MNT1_NEUTRAL_X, Y, Z)

  3. MAVLink Targeting : gimbal’s angle or rate targets are controlled via mavlink messages (see MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW). It is not necessary to specifically change to this mode, this will happen automatically if MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW is sent

  4. RC Targeting : pilot controls the gimbal angle or rate using RC input (see MNT_RC_IN_PAN/ROLL/TILT and MNT_RC_RATE parameters)

  5. GPS Point: gimbal points towards a Location (Lat, Lon, Alt) (see MAV_CMD_DO_SET_ROI). It is not necessary to specifically change to this mode, this will happen automatically if MAV_CMD_DO_SET_ROI is sent

  6. SysId Target: gimbal points towards another vehicle (see MAV_CMD_DO_SET_ROI_SYSID). It is not necessary to specifically change to this mode, this will happen automatically if MAV_CMD_DO_SET_ROI_SYSID is sent

  7. Home Location: gimbal points towards home

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
command uint16_t MAV_CMD_DO_MOUNT_CONTROL=205
confirmation uint8_t 0
param1 float Pitch in degrees (or zero)
param2 float Roll in degrees (or zero)
param3 float Yaw in degrees (or zero)
param4 float Altitude in meters (or zero)
param5 float Longitude in degrees * 1E7 (or zero)
param6 float Latitude in degrees * 1E7 (or zero)
param7 float Mode (0=Retract, 1=Neutral, 2=Mavlink Targeting, 3=RC Targeting, 4=GPS Point, 5=SysId Target, 6=Home Location)

Example

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter

  • module load message

Example MAVProxy/SITL Command

Description

message COMMAND_LONG 0 0 205 0 0 0 0 0 0 0 0

Retract Gimbal

message COMMAND_LONG 0 0 205 0 0 0 0 0 0 0 2

Switch to MAVLink Targeting (MAVLink messages control gimbal)

message COMMAND_LONG 0 0 205 0 0 0 0 0 0 0 3

Switch to RC Targeting (Pilot controls gimbal from RC)

message COMMAND_LONG 0 0 205 0 0 0 0 0 0 0 5

Point gimbal at another vehicle see MAV_CMD_DO_SET_ROI_SYSID

message COMMAND_LONG 0 0 205 0 0 0 0 0 0 0 6

Point gimbal at home

MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW to move to a desired angle or at a desired rate

The gimbal’s attitude can be changed to a desired pitch and yaw angle or changed at a desired rate by sending a COMMAND_LONG with the command and param1 through param7 fields set as specified for the MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW command.

The gimbal’s yaw behaviour as the vehicle rotates can also be controlled. The two behaviour are:

  • body-frame/follow means the gimbal’s yaw will rotate with the vehicle

  • earth-frame / lock means the gimbal’s yaw will remain fixed and will not rotate with the vehicle

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
command uint16_t MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW=1000
confirmation uint8_t 0
param1 float Pitch angle in deg (positive is up) or NaN if unused
param2 float Yaw angle in deg (positive is clockwise) or NaN if unused
param3 float Pitch rate in deg/s (positive is up) or NaN if unused
param4 float Yaw rate in deg/s (positive is clockwise) or NaN if unused
param5 float Flags (0=Yaw is body-frame/follow, 16=Yaw is earth-frame/lock)
param6 float not used
param7 float Gimbal device ID (0 is primary gimbal, 1 is 1st gimbal, 2 is 2nd gimbal)

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter:

  • module load message

Example MAVProxy/SITL Command

Description

message COMMAND_LONG 0 0 1000 0 -20 90 float("NaN") float("NaN") 0 0 0

Pitch down 20deg, yaw right 90 deg, body-frame / follow

message COMMAND_LONG 0 0 1000 0 -20 90 float("NaN") float("NaN") 16 0 0

Pitch down 20deg, yaw East, earth-frame / lock

message COMMAND_LONG 0 0 1000 0 float("NaN") float("NaN") 5 0 0 0 0

Pitch down at 5deg/sec, yaw hold, body-frame / follow

message COMMAND_LONG 0 0 1000 0 float("NaN") float("NaN") 0 5 0 0 0

Pitch hold, yaw clockwise at 5deg/sec in body-frame

message COMMAND_LONG 0 0 1000 0 float("NaN") float("NaN") 0 5 16 0 0

Pitch hold, yaw clockwise at 5deg/sec in eartj-frame

MAV_CMD_DO_SET_ROI_LOCATION to point at a Location

The gimbal can be pointed at a Location (Lat, Lon, Alt) by sending a COMMAND_INT with the command and param1 through param6 fields set as specified for the MAV_CMD_DO_SET_ROI_LOCATION command.

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
frame uint8_t

Valid options are:

  • MAV_FRAME_GLOBAL (0): alt is meters above sea level

  • MAV_FRAME_GLOBAL_INT (5): alt is meters above sea level

  • MAV_FRAME_GLOBAL_RELATIVE_ALT (3): alt is meters above home

  • MAV_FRAME_GLOBAL_RELATIVE_ALT_INT (6): alt is meters above home

  • MAV_FRAME_GLOBAL_TERRAIN_ALT (10): alt is meters above terrain

  • MAV_FRAME_GLOBAL_TERRAIN_ALT_INT (11): alt is meters above terrain

command uint16_t MAV_CMD_DO_SET_ROI_LOCATION=195
current uint8_t 0 (not used)
autocontinue uint8_t 0 (not used)
param1 float Gimbal device id (unused)
param2 float not used
param3 float not used
param4 float not used
param5 int32_t Latitude in degrees * 10^7
param6 int32_t Longitude in degrees * 10^7
param7 float Altitude in meters

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter:

  • module load message

Example MAVProxy/SITL Command

Description

message COMMAND_INT 0 0 6 195 0 0 0 0 0 0 -353632632 1491663846 10

Point at Lat:-35.3632632 Lon:149.1663846 Alt:10m above home

message COMMAND_INT 0 0 0 195 0 0 0 0 0 0 -353632632 1491663846 10

Point at Lat:-35.3632632 Lon:149.1663846 Alt:10m above sea level

message COMMAND_INT 0 0 11 195 0 0 0 0 0 0 -353632632 1491663846 10

Point at Lat:-35.3632632 Lon:149.1663846 Alt:10m above terrain

MAV_CMD_DO_SET_ROI_NONE to stop pointing at a Location

The gimbal ROI can be stopped (e.g. the gimbal will switch to its default mode held in the MNT1_DEFLT_MODE param)) by sending a COMMAND_INT with the command and param1 specified for the MAV_CMD_DO_SET_ROI_NONE command.

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
frame uint8_t 0 (not used)
command uint16_t MAV_CMD_DO_SET_ROI_NONE=197
current uint8_t 0 (not used)
autocontinue uint8_t 0 (not used)
param1 float Gimbal device id (unused)
param2 float not used
param3 float not used
param4 float not used
param5 int32_t not used
param6 int32_t not used
param7 float not used

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter:

  • module load message

Example MAVProxy/SITL Command

Description

message COMMAND_INT 0 0 0 197 0 0 0 0 0 0 0 0 0

Stop pointing at a Location or another vehicle (gimbal will return to its default mode)

MAV_CMD_DO_SET_ROI_SYSID to point at another vehicle

The gimbal can be pointed at another vehicle by sending a COMMAND_LONG with the command and param1 fields set as specified for the MAV_CMD_DO_SET_ROI_SYSID command.

This feature relies on the main vehicle receiving the other vehicle’s position at regular intervals via the GLOBAL_POSITION_INT message.

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
command uint16_t MAV_CMD_DO_SET_ROI_SYSID=198
confirmation uint8_t 0
param1 float System ID of other vehicle
param2 float Gimbal device id (unused)
param3 float unused
param4 float unused
param5 float unused
param6 float unused
param7 float unused

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter:

  • module load message

Example MAVProxy/SITL Command

Description

message COMMAND_LONG 0 0 198 0 2 0 0 0 0 0 0

Point at vehicle with SysId=2

MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE to take control of the gimbal (optional)

The MAVLink Gimbalv2 protocol includes support for deconflicting commands received simultaneously from multiple MAVLink enabled ground stations using the DO_GIMBAL_MANAGER_CONFIGURE command. ArduPilot consumes these commands and reports who is in control using the GIMBAL_MANAGER_STATUS message but does not actually enforce their use due to concerns around backwards compatibility and the number of support calls this would generate.

A ground station (or other MAVLink enabled device) can take control of the gimbal by sending a COMMAND_LONG with the command and param1 fields set as specified for the MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE command.

Command Field Type Description
target_system uint8_t System ID of flight controller or just 0
target_component uint8_t Component ID of flight controller or just 0
command uint16_t MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE=1001
confirmation uint8_t 0
param1 float System ID for primary control (0:no one, -1:leave unchanged, -2:set self in control, -3:release control)
param2 float Component ID for primary control
param3 float System ID for secondary control (unused)
param4 float Component ID for secondary control (unused)
param5 float unused
param6 float unused
param7 float Gimbal device ID (0 is primary gimbal, 1 is 1st gimbal, 2 is 2nd gimbal)

The example commands below can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands enter:

  • module load message

Example MAVProxy/SITL Command

Description

message COMMAND_LONG 0 0 511 0 281 1000000 0 0 0 0 0

request GIMBAL_MANAGER_STATUS at 1hz

message COMMAND_LONG 0 0 1001 0 -2 0 0 0 0 0 0

set self in control

message COMMAND_LONG 0 0 1001 0 -3 0 0 0 0 0 0

release control

message COMMAND_LONG 0 0 1001 0 123 1 0 0 0 0 0

set sysid:123 / compid:1 in control

You can see the results of by monitoring the GIMBAL_MANAGER_STATUS message

  • status GIMBAL_MANAGER_STATUS