MAVLink Communication
this page is under construction, and for the moment mainly serves the author as reference
The information on this page refers to firmware v2.42c and higher.
In addition to the serial commands, the STorM32 controller also understands MAVLink messages, as defined in the MAVLink standard. The STorM32 controller in fact supports a very rich set of MAVLink messages and features, as well as the MAVLink2 protocol, and might be by far the most integrated MAVLink capable gimbal controller available.
The STorM32 controller integrates two MAVLink components, which in the following will be referred to as MAVLink Gimbal and as MAVLink Camera.
- The MAVLink Gimbal is the part which deals with the gimbal operation. That's the part you got to know in older firmware versions.
- The MAVLink Camera is related to the NT Camera, and provides a camera protocol micro service. It allows you to control the camera through MAVLink in unprecedented useful ways.
When the STorM32 controller receives valid MAVLink messages and a MAVLink connection is established, the MAVLINK field in the [GUI:Dashboard] will change to displaying MAVLINK is PRESENT.
MAVLink Gimbal
In order to enable the MAVLink Gimbal, the emission of a heartbeat must be enabled by setting the Mavlink Configuration parameter accordingly.
The STorM32's system ID and component ID can be adjusted in the GUI. The defaults are
- Mavlink System ID = “1”
- Mavlink Component ID = “154” (= MAV_COMP_ID_GIMBAL)
The System ID should be matched to the system ID of the autopilot. The Component ID should usually not be changed.
The STorM32 supports MAVLink1 and MAVLink2, which can be set via the parameter Mavlink Version. Per default MAVLink2 is disabled, for compatibility reasons. It is however recommended to enable MAVLink2.
The following MAVLink messages are supported:
MAVLINK_MSG_ID_HEARTBEAT (#0, 0x00)
See HEARTBEAT.
The emission of the heartbeat needs to be activated in the GUI via the Mavlink Configuration parameter. The heartbeat is emitted at 1 Hz, with the following values:
- type: MAV_TYPE_GIMBAL (= 26)
- autopilot: MAV_AUTOPILOT_INVALID (= 8)
- base_mode: either 0 or MAV_MODE_FLAG_SAFETY_ARMED (= 0x80)
- custom_mode: STATE value of the o323bgc firmware
- system_status: either MAV_STATE_BOOT (= 1) or MAV_STATE_ACTIVE (= 4)
MAVLINK_MSG_ID_PARAM_REQUEST_READ (#20, 0x14)
See PARAM_REQUEST_READ.
MAVLINK_MSG_ID_PARAM_REQUEST_LIST (#21, 0x15)
See PARAM_REQUEST_LIST.
MAVLINK_MSG_ID_PARAM_VALUE (#22, 0x16)
See PARAM_VALUE.
MAVLINK_MSG_ID_PARAM_SET (#23, 0x17)
See PARAM_SET.
MAVLINK_MSG_ID_ATTITUDE (#30, 0x1E)
See ATTITUDE.
The emission of the attitude message with 2 Hz can be activated in the GUI via the Mavlink Configuration parameter, or by requesting a data stream with MESSAGE_INTERVAL. The yaw angle is relative to the forward direction.
MAVLINK_MSG_ID_RC_CHANNLES (#65, 0x41)
See RC_CHANNELS.
MAVLINK_MSG_ID_REQUEST_DATA_STREAM (#66, 0x42)
See REQUEST_DATA_STREAM.
This message is sent out with req_stream_id = MAV_DATA_STREAM_RC_CHANNELS and req_message_rate = 10, when an ArduPilot autopilot (= MAV_AUTOPILOT_ARDUPILOTMEGA) is detected.
MAVLINK_MSG_ID_COMMAND_LONG (#76, 0x4C)
See COMMAND_LONG.
Each command is acknowledged with a COMMAND_ACK message. The following commands are supported (parameter fields not mentioned are ignored):
MAV_CMD_DO_SET_PARAMETER (#180, 0xB4) * param1 = parameter index * param2 = parameter value
MAV_CMD_DO_SET_SERVO (#183, 0xB7) * param2 = pwm value (only 700...2300 accepted)
MAV_CMD_DO_DIGICAM_CONFIGURE (#202, 0xCA) is just there so that a COMMAND_ACK with MAV_CMD_ACK_OK is returned
MAV_CMD_DO_DIGICAM_CONTROL (#203, 0xCB) * param5 = shot (0 = off, 1 = IRSHUTTER)
MAV_CMD_DO_MOUNT_CONFIGURE (#204, 0xCC) * param1 = mount_mode (0 = MAV_MOUNT_MODE_RETRACT and 1 = MAV_MOUNT_MODE_NEUTRAL recenters the camera)
MAV_CMD_DO_MOUNT_CONTROL (#205, 0xCD) * param1 = pitch, angle in degree (COMMENT: the sign is opposite to convention!) * param2 = roll, angle in degree * param3 = yaw, angle in degree (COMMENT: the sign is opposite to convention!) * param7 = mount_mode (0 = MAV_MOUNT_MODE_RETRACT and 1 = MAV_MOUNT_MODE_NEUTRAL recenters the camera)
MAV_CMD_DO_SET_CAM_TRIGG_DIST(#206, 0xCE) * param3 = trigger camera once immediately (0 = off, 1 = IRSHUTTER)
MAV_CMD_PREFLIGHT_STORAGE (#245, 0xF5) * param1 = parameter storage 0: restore parameter values from EEPROM 1: store parameter values in EEPROM 2: ignored, as it maybe harmful
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN(#246, 0xF6) * param4 1: restart with full reset 2: ishut down motors
MAV_CMD_SET_MESSAGE_INTERVAL (#511, 0x01FF) * param1 = MAVLink message ID; the attitude and mount status can be requested * param2 = interval between two messages, in microseconds; set to -1 to disable
MAV_CMD_REQUEST_MESSAGE (#512, 0x0200) * param1 = message ID of the requested message 30: send attitude 158: send mount status 265: send mount orientation
MAV_CMD_REQUEST_PROTOCOL_VERSION (#519, 0x0207) send PROTOCOL_VERSION message
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES (#520, 0x0208) send AUTOPILOT_VERSION message
MAV_CMD_REQUEST_COMPONENT_INFORMATION (#700) send COMPONENT_INFORMATION message this is not official and work in progress, see https://github.com/mavlink/mavlink/issues/1133
MAVLINK_MSG_ID_COMMAND_ACK (#77, 0x4D)
See COMMAND_ACK.
MAVLINK_MSG_ID_AUTOPILOT_VERSION (#148, 0x94)
See AUTOPILOT_VERSION.
MAVLINK_MSG_ID_MOUNT_STATUS (#158, 0x9E)
ArduPilot specific message. See MOUNT_STATUS.
The emission of the mount status message with 2 Hz can be activated in the GUI via the Mavlink Configuration parameter, or by requesting a data stream with MESSAGE_INTERVAL. The yaw angle is relative to the forward direction. The target is set to target_system = 0, target_component = 0.
MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST (#183, 0xB7)
ArduPilot specific message. See AUTOPILOT_VERSION_REQUEST.
MAVLINK_MSG_ID_MESSAGE_INTERVAL (#244, 0xF4)
See MESSAGE_INTERVAL.
The attitude, the mount status, or the mount orientation can be requested.
MAVLINK_MSG_ID_STATUSTEXT (#253, 0xFD)
See STATUSTEXT.
This message is sent out after a PARAM_REQUEST_LIST has been served, and provides firmware and board type information.
MAVLINK_MSG_ID_MOUNT_ORIENTATION (#265, 0x109)
See MOUNT_ORIENTATION.
The emission of the mount orientation message with 2 Hz can be activated in the GUI via the Mavlink Configuration parameter, or by requesting a data stream with MESSAGE_INTERVAL. The yaw angle is relative to the forward direction.
MAVLINK_MSG_ID_PROTOCOL_VERSION (#300, 0x12C)
See PROTOCOL_VERSION.
MAVLINK_MSG_ID_COMPONENT_INFORMATION (#700)
This is not official and work in progress, see https://github.com/mavlink/mavlink/issues/1133.
MAVLink Camera
The MAVLink Camera is independent on the MAVLink Gimbal. That is, it can be used also then the MAVLink Gimbal is disabled (Mavlink Configuration = “no heartbeat”), and vice versa.
The setting in the Mavlink Camera parameter enables the MAVLink Camera. In addition, MAVLink2 must be enabled , by setting Mavlink Version accordingly, for the camera protocol micro service to work, which is the cool part of the MAVLink Camera.
The system ID of the MAVLink Camera is determined by the same parameter Mavlink System ID as before. The component ID is determined by the setting in Mavlink Camera: “Camera1” corresponds to MAV_COMP_ID_CAMERA (= 100), “Camera2” to MAV_COMP_ID_CAMERA2 (= 101), and so on.
The MAVLink Camera is deeply related to the NT Camera and the IR Camera parameter settings in the [GUI:Functions] tab.
The following MAVLink messages are supported:
MAVLINK_MSG_ID_HEARTBEAT (#0, 0x00)
See HEARTBEAT.
The emission of the heartbeat needs to be activated in the GUI via the Mavlink Camera parameter. The heartbeat is emitted at 1 Hz, with the following values:
- type: MAV_TYPE_CAMERA (= 30)
- autopilot: MAV_AUTOPILOT_INVALID (= 8)
- base_mode: 0
- custom_mode: 0
- system_status: MAV_STATE_ACTIVE
MAVLINK_MSG_ID_PARAM_REQUEST_READ (#20, 0x14)
See PARAM_REQUEST_READ.
MAVLINK_MSG_ID_PARAM_REQUEST_LIST (#21, 0x15)
See PARAM_REQUEST_LIST.
MAVLINK_MSG_ID_PARAM_VALUE (#22, 0x16)
See PARAM_VALUE.
MAVLINK_MSG_ID_PARAM_SET (#23, 0x17)
See PARAM_SET.
MAVLINK_MSG_ID_COMMAND_LONG (#76, 0x4C)
See COMMAND_LONG.
Each command is acknowledged with a COMMAND_ACK message. The following commands are supported (parameter fields not mentioned are ignored):
MAV_CMD_REQUEST_PROTOCOL_VERSION (#519, 0x0207) send PROTOCOL_VERSION message
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES (#520, 0x0208) send AUTOPILOT_VERSION message
MAV_CMD_REQUEST_CAMERA_INFORMATION (#521, 0x0209) * param1 = request camera capabilities 1: send CAMERA_INFORMATION message
MAV_CMD_REQUEST_CAMERA_SETTINGS (#522, 0x020A) send CAMERA_SETTINGS message
MAV_CMD_REQUEST_STORAGE_INFORMATION (#525, 0x020D) send STORAGE_INFORMATION message
MAV_CMD_STORAGE_FORMAT (#526, 0x020E) a COMMAND_ACK with MAV_CMD_ACK_DENIED is returned
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (#527, 0x020F) send CAMERA_CAPTURE_STATUS message
MAV_CMD_RESET_CAMERA_SETTINGS (#529, 0x0211) a COMMAND_ACK with MAV_CMD_ACK_DENIED is returned
MAV_CMD_SET_CAMERA_MODE (#530, 0x0212) * param2 = camera mode
MAV_CMD_SET_CAMERA_ZOOM (#531, 0x0213) a COMMAND_ACK with MAV_CMD_ACK_DENIED is returned
MAV_CMD_SET_CAMERA_FOCUS (#532, 0x0214) a COMMAND_ACK with MAV_CMD_ACK_DENIED is returned
MAV_CMD_IMAGE_START_CAPTURE (#2000, 0x07D0) * param2 = desired elapsed time between two consecutive pictures (in seconds) * param3 = total number of images to capture * param4 = capture sequence number starting
MAV_CMD_IMAGE_STOP_CAPTURE (#2001, 0x07D18)
MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE (#2002, 0x07D2) a COMMAND_ACK with MAV_CMD_ACK_DENIED is returned
MAV_CMD_VIDEO_START_CAPTURE (#2500, 0x09C4) * param1 = video stream ID * param2 = frequency CAMERA_CAPTURE_STATUS messages should be sent while recording
MAV_CMD_VIDEO_STOP_CAPTURE (#2501, 0x09C5) * param1 = video stream ID
MAVLINK_MSG_ID_COMMAND_ACK (#77, 0x4D)
See COMMAND_ACK.
MAVLINK_MSG_ID_AUTOPILOT_VERSION (#148, 0x94)
See AUTOPILOT_VERSION.
MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST (#183, 0xB7)
ArduPilot specific message. See AUTOPILOT_VERSION_REQUEST.
MAVLINK_MSG_ID_CAMERA_INFORMATION (#259, 0x103)
See CAMERA_INFORMATION.
MAVLINK_MSG_ID_CAMERA_SETTINGS (#260, 0x104)
See CAMERA_SETTINGS.
MAVLINK_MSG_ID_STORAGE_INFORMATION (#261, 0x105)
See STORAGE_INFORMATION.
MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS (#262, 0x106)
MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED (#263, 0x107)
MAVLINK_MSG_ID_PROTOCOL_VERSION (#300, 0x12C)
See PROTOCOL_VERSION.
MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ (#320, 0x140)
MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST (#321, 0x141)
MAVLINK_MSG_ID_PARAM_EXT_VALUE (#322, 0x142)
See PARAM_EXT_VALUE.
MAVLINK_MSG_ID_PARAM_EXT_SET (#323, 0x143)
See PARAM_EXT_SET.
MAVLINK_MSG_ID_PARAM_EXT_ACK (#324, 0x144)
See PARAM_EXT_ACK.