Control a Camera

This page explains how MAVLink can be used to control a camera. These commands are supported in ArduPilot 4.3.x and earlier:

  • MAV_CMD_DO_DIGICAM_CONTROL to take a picture

  • MAV_CMD_DO_SET_CAM_TRIGG_DIST to take pictures at regular distance intervals

These commands are supported in ArduPilot 4.4.0 and higher:

  • MAV_CMD_IMAGE_START_CAPTURE to take a picture

  • MAV_CMD_SET_CAMERA_ZOOM to control the camera zoom

  • MAV_CMD_SET_CAMERA_FOCUS to manually or automatically focus the camera

  • MAV_CMD_VIDEO_START_CAPTURE to start recording video

  • MAV_CMD_VIDEO_STOP_CAPTURE to stop recording a video

These commands and messages are not yet supported but may be in future releases

  • MAV_CMD_REQUEST_CAMERA_INFORMATION

  • MAV_CMD_REQUEST_CAMERA_SETTINGS

  • MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS

  • MAV_CMD_RESET_CAMERA_SETTINGS

  • MAV_CMD_SET_CAMERA_MODE

  • MAV_CMD_IMAGE_STOP_CAPTURE

  • MAV_CMD_DO_TRIGGER_CONTROL

  • MAV_CMD_CAMERA_TRACK_POINT to initiate tracking of a point on the video feed

  • MAV_CMD_CAMERA_TRACK_RECTANGLE to initiate tracking of a rectangle on the video feed

  • MAV_CMD_CAMERA_STOP_TRACKING to stop tracking

  • MAV_CMD_VIDEO_START_STREAMING and MAV_CMD_VIDEO_STOP_STREAMING to start and stop streaming a video to the ground station

  • MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION

  • MAV_CMD_REQUEST_VIDEO_STREAM_STATUS

  • CAMERA_INFORMATION

  • CAMERA_SETTINGS

  • CAMERA_CAPTURE_STATUS

  • CAMERA_IMAGE_CAPTURED

  • CAMERA_FOV_STATUS

  • CAMERA_TRACKING_IMAGE_STATUS

  • CAMERA_TRACKING_GEO_STATUS

Note

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

MAV_CMD_DO_DIGICAM_CONTROL to take a picture

A picture can be taken by sending a COMMAND_LONG with the command and param5 fields set as specified for the MAV_CMD_DO_DIGICAM_CONTROL 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_DIGICAM_CONTROL=203
confirmation uint8_t 0
param1 float Session Control (unused)
param2 float Zoom Absolute (unused)
param3 float Zoom Relative (unused)
param4 float Focus (unused)
param5 float Shoot Command=1
param6 float Command Identify (unused)
param7 float Shot ID (unused)

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 203 0 0 0 0 0 1 0 0

Take a picture

MAV_CMD_DO_SET_CAM_TRIGG_DIST to take a picture at regular distance intervals

A picture can be taken at regular distance intervals by sending a COMMAND_LONG with the command and param fields set as specified for the MAV_CMD_DO_SET_CAM_TRIGG_DIST 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_SET_CAM_TRIGG_DIST=206
confirmation uint8_t 0
param1 float Distance in meters or 0 to stop triggering
param2 float Shutter (unused)
param3 float Trigger camera once immediately. (0 = no trigger now, 1 = trigger now)
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 206 0 10 0 0 0 0 0 0

Take a picture every 10m

message COMMAND_LONG 0 0 206 0 10 0 1 0 0 0 0

Take a picture now and then again every 10m

message COMMAND_LONG 0 0 206 0 0 0 0 0 0 0 0

Stop taking pictures at regular intervals

MAV_CMD_IMAGE_START_CAPTURE to take a picture

A picture can be taken by sending a COMMAND_LONG with the command and param3 fields set as specified for the MAV_CMD_IMAGE_START_CAPTURE 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_IMAGE_START_CAPTURE=2000
confirmation uint8_t 0
param1 float unused
param2 float Interval=0 (unsupported)
param3 float Total Images=1 (multiple images not supported)
param4 float Sequence Number (unsupported)
param5 float Sequence Number (unsupported)
param6 float unused
param7 float unused

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 2000 0 0 0 1 0 0 0 0

Take a picture

MAV_CMD_SET_CAMERA_ZOOM to control the camera zoom

The camera zoom can be controlled by sending a COMMAND_LONG with the command and param fields set as specified for the MAV_CMD_SET_CAMERA_ZOOM 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_SET_CAMERA_ZOOM=531
confirmation uint8_t 0
param1 float Zoom Type=1 (step=0, continous=1, range=2, focal length=3)
param2 float Zoom Value (zoom in=1, zoom out=-1, stop=0)
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 531 0 1 1 0 0 0 0 0

Zoom in

message COMMAND_LONG 0 0 531 0 1 -1 0 0 0 0 0

Zoom out

message COMMAND_LONG 0 0 531 0 1 0 0 0 0 0 0

Stop zooming in or out

MAV_CMD_SET_CAMERA_FOCUS to manually or automatically focus the camera

The camera zoom can be controlled by sending a COMMAND_LONG with the command and param fields set as specified for the MAV_CMD_SET_CAMERA_FOCUS 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_SET_CAMERA_FOCUS=532
confirmation uint8_t 0
param1 float Focus Type=1 OR 4 (step=0, continous=1, range=2, meters=3, auto=4, auto single=5, auto continuous=6)
param2 float Focus Value (focus in=-1, focus out=1, hold=0)
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 532 0 1 -1 0 0 0 0 0

Manual focus in

message COMMAND_LONG 0 0 532 0 1 1 0 0 0 0 0

Manual focus out

message COMMAND_LONG 0 0 532 0 1 0 0 0 0 0 0

Manual focus hold

message COMMAND_LONG 0 0 532 0 4 0 0 0 0 0 0

Auto focus

MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_STOP_CAPTURE to start or stop recording video

To start or stop recording video send a COMMAND_LONG with the command and param fields set as specified for the MAV_CMD_VIDEO_START_CAPTURE or MAV_CMD_VIDEO_STOP_CAPTURE commands.

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_VIDEO_START_CAPTURE=2500, MAV_CMD_VIDEO_STOP_CAPTURE=2501
confirmation uint8_t 0
param1 float Stream ID (All=0, 1st camera=1, 2nd camera=2)
param2 float Status Frequency (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 2500 0 0 0 0 0 0 0 0

Start recording video on all cameras

message COMMAND_LONG 0 0 2500 0 1 0 0 0 0 0 0

Start recording video on 1st camera

message COMMAND_LONG 0 0 2501 0 0 1 0 0 0 0 0

Stop recording video on all cameras

message COMMAND_LONG 0 0 2501 0 1 0 0 0 0 0 0

Stop recording video on 1st camera