MAVLink Communication: Difference between revisions
Line 249: | Line 249: | ||
See [https://mavlink.io/en/messages/common.html#MOUNT_ORIENTATION MOUNT_ORIENTATION]. | See [https://mavlink.io/en/messages/common.html#MOUNT_ORIENTATION MOUNT_ORIENTATION]. | ||
The emission of the mount orientation message with 4 Hz can be activated in the GUI via the {{PARAMNAME|Mavlink Gimbal Stream}} parameter, | The emission of the mount orientation message with 4 Hz can be activated in the GUI via the {{PARAMNAME|Mavlink Gimbal Stream}} parameter, and by requesting a data stream or single-shot emission with the MAV_CMD_SET_MESSAGE_INTERVAL or MAV_CMD_REQUEST_MESSAGE commands, respectively. The yaw angle is relative to the forward direction. | ||
==== MAVLINK_MSG_ID_PROTOCOL_VERSION (#300, 0x12C) ==== | ==== MAVLINK_MSG_ID_PROTOCOL_VERSION (#300, 0x12C) ==== |
Revision as of 15:48, 12 October 2019
The information on this page refers to firmware v2.43 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 rich set of MAVLink messages and features, as well as the MAVLink 2 protocol, and might be by far the most integrated MAVLink capable gimbal controller available.
The STorM32 controller integrates two MAVLink components, which are referred to as the MAVLink Gimbal and MAVLink Camera components:
- MAVLink Gimbal: This component deals with the gimbal operation, and is the part which you know from older firmware versions.
- MAVLink Camera: This component is related to the NT Camera, and provides a complete MAVLink Camera Protocol microservice server. It allows you to control the camera through MAVLink in unprecedented useful ways.
The MAVLink Gimbal and MAVLink Camera components share some parameters, but function-wise are independent of each other. That is, both can be used simultaneously, the MAVLink Gimbal component can be used alone without the MAVLink Camera component, and vice versa.
Comment: The MAVLINK field in the [GUI:Dashboard] Info Center shows MAVLINK is PRESENT when the STorM32 controller is receiving valid MAVLink messages, implying a MAVLink connection is established. This can be handy for diagnosis.
Comment: In case you find it confusing what "two MAVLink components" is supposed to mean, then just connect the STorM32 controller (with both components enabled) to MissionPlanner: You will find that it will show you two components, one named GIMBAL and the other named CAMERA :).
Parameters
The MAVLink parameters are located in the [GUI:Interfaces Tool] window, which is accessible via the [GUI:Experts Only] menu.
It has the following parameters:
- Mavlink Gimbal: Enables the MAVLink Gimbal component and sets its component ID.
- Mavlink Gimbal Stream: Activates emission of the selected message by the Gimbal component.
- Mavlink ComPort: Selects the serial com port which shall be used for the MAVLink communication. Applies to both the MAVLink Gimbal and MAVLink Camera components.
- Mavlink System ID: Sets the system ID of the STorM32 controller (default = “0”). Applies to both the MAVLink Gimbal and MAVLink Camera components. If it is set to “0”, then the system ID is autodetected, i.e., the STorM32 waits for incoming heartbeat messages from an autopilot and then uses its system ID.
- Mavlink Version: Sets the used MAVLink protocol version (default = “Mavlink2”). Applies to both the MAVLink Gimbal and MAVLink Camera components. Must be set to “Mavlink2” for the MAVLink Camera component to fully work.
- Mavlink Camera: Enables the MAVLink Camera component and sets its component ID.
The STorM32 system ID should match the system ID of the autopilot, or autodetection should be enabled with Mavlink System ID = “0” (which is the default).
STorM32 supports the MAVLink 1 and MAVLink 2 protocols, which can be set via the parameter Mavlink Version. Per default MAVLink 2 is enabled, and it is highly recommended to use it.
Comment: The STorM32 controller always accepts and serves incoming MAVLink messages on any of its serial ports, irrespective of the Mavlink Gimbal, Mavlink Camera and Mavlink ComPort settings. However, all outgoing messages such as heartbeats are emitted only on the selected serial port, and this port also does not accept incoming serial commands, i.e., is exclusive for MAVLink communication.
Comment: The baudrate of the selected serial port is determined by the respective baudrate parameter in the [GUI:Expert] tab. Per default it is 115200 bps. It is recommended to use a baudrate of 230400 bps, if possible.
Comment: For v1.x boards: When the UART port is selected, one cannot use a BT module and a serial MAVLink connection at the same time.
Pass-Through
It is possible to connect the STorM32 GUI to any routing component in a MAVLink system, such as an autopilot or on-board companion computer, and to communicate directly with the STorM32 gimbal via MAVLink tunnel messages.
This is extremely convenient when the STorM32 gimbal is permanently installed in a vehicle, as it allows us to configure the gimbal without having to have physical access to the STorM32's USB or UART ports. The pass-through also works with wireless telemetry links, which opens up options such as tuning the gimbal during flight, and other unheard-of possibilities for in-flight control of the gimbal.
The pass-through mode of operation is enabled by checking in the GUI the [MAVLink] checkbox, which is located next to the [Port] combobox. The GUI then effectively operates like a mini MAVLink ground control station (the system ID is determined from the attached components, its component ID is MAV_COMP_ID_TUNNEL_NODE = 242 per default).
Comment: The pass-through communication is based on standard MAVLink, and thus should work for any MAVLink compatible autopilot.
Comment: Pass-through works for both the MAVLink Gimbal and MAVLink Camera components. The GUI chooses the MAVLink Gimbal if enabled, otherwise the MAVLink Camera for communication.
Comment: GUI functions which need physical access to a USB/UART port on the STorM32 controller do not work in pass-through mode. For instance, upgrading firmwares won't work.
This preliminary demo video demonstrates the pass-through feature:
MAVLink FTP
The MAVLink Camera component supports the MAVLink FTP micro service to the extend that it allows downloading the camera definition files stored in the STorM32 controller.
For the MAVLink Gimbal component, MAVLink FTP is momentarily disabled, as there is no use case currently.
Supported OpCodes/Commands
These opcodes/commands are support (unsupported commands will be NACKed with error code Fail):
MAVFTP_OPCODE_None MAVFTP_OPCODE_TerminateSession MAVFTP_OPCODE_ResetSessions MAVFTP_OPCODE_ListDirectory MAVFTP_OPCODE_OpenFileRO MAVFTP_OPCODE_ReadFile MAVFTP_OPCODE_CalcFileCRC32
Comments on Compatibility
The MAVLink messages and commands related to the control of a gimbal as used by ArduPilot-based systems are somewhat of a mess; they suffer from history, bugs, and wrong usage. This has lead to a variety of issues.
A drastic example is the 3DR Solo drone. Here the issue is a combination of all of them, the infamous "reversed signs", use of the non-standard/deprecated messages, and improper use of target system and component IDs: ArduPilot supports the official COMMAND_LONG commands (see Gimbal protocol) as well as it's own MOUNT_CONFIGURE and MOUNT_CONTROL messages. For that reason, the STorM32 controller of course also supported these. However, the 3DR Solo firmware emits MOUNT_CONFIGURE/MOUNT_CONTROL messages with target (0,1), which are forwarded to the gimbal according to the MAVLink routing rules, whereas the ArduPilot mount class sends MAV_CMD_DO_MOUNT_CONTROL commands to the gimbal. This leads to the situation that the STorM32 receives both the commands and the messages, which however carry conflicting data, and in addition there is a bug in the ArduPilot code.
Therefore, the STorM32's behavior has been changed with firmware v2.42: The ArduPilot-specific MOUNT_CONFIGURE and MOUNT_CONTROL messages are not supported anymore, except if explicitly asked for by setting Mavlink Version = “Mavlink1+v0.96”.
This resolves issues like those with the 3DR Solo: The messages send out by the Solo and forwarded to the STorM32 are ignored, so that the STorM32 only acts on the proper commands from the flight controller (this still doesn't make things work very well in MAVLINK_TARGETING mode however due to another bug in the ArduPilot code, but that's the best the STorM32 can do).
MAVLink Gimbal
The MAVLink Gimbal component is enabled with the Mavlink Gimbal parameter, which also determines its component ID: “Gimbal1” corresponds to MAV_COMP_ID_GIMBAL (= 154), “Gimbal2” to MAV_COMP_ID_GIMBAL2 (= 171), “Gimbal3” to MAV_COMP_ID_GIMBAL3 (= 172), and so on:
- Mavlink Gimbal = “Gimbal1” or higher
- Mavlink Gimbal Stream: Activates the emission of the selected message with a frequency of 4 Hz.
The system ID can be adjusted via the Mavlink System ID parameter, which usually can be left at its default value.
With the setting Mavlink Version = “Mavlink1+v0.96”, the "old" MAVLink behavior is enabled. Especially, the ArduPilot-specific messages DIGICAM_CONTROL, MOUNT_CONFIGURE, and MOUNT_CONTROL are then also supported.
Messages
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 Gimbal parameter. The heartbeat is emitted at 1 Hz, with the following values:
- type: MAV_TYPE_GIMBAL (= 26)
- autopilot: MAV_AUTOPILOT_INVALID (= 8)
- base_mode: MAV_MODE_FLAG_SAFETY_ARMED (= 0x80) is set in NORMAL mode, MAV_MODE_FLAG_CUSTOM_MODE_ENABLED (= 0x01) is always set
- custom_mode: STATE value of the o323bgc firmware
- system_status: either MAV_STATE_BOOT (= 1), MAV_STATE_ACTIVE (= 4) or MAV_STATE_EMERGENCY (= 6)
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 4 Hz can be activated in the GUI via the Mavlink Gimbal Stream parameter, or by requesting a data stream using the MAV_CMD_SET_MESSAGE_INTERVAL command. The yaw angle is relative to the forward direction.
MAVLINK_MSG_ID_RC_CHANNLES (#65, 0x41)
See RC_CHANNELS.
When an ArduPilot autopilot (= MAV_AUTOPILOT_ARDUPILOTMEGA) is detected, streaming of this message by the autopilot is requested with req_stream_id = MAV_DATA_STREAM_RC_CHANNELS and req_message_rate = 10.
The parameter Virtual Channel Configuration needs to be set to “serial” for the values received by this message to become available for inputs as “Virtual-1” to “Virtual-16”.
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 = SHUTTER)
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: shut down motors
MAV_CMD_GET_MESSAGE_INTERVAL (#510, 0x01FE) * param1 = MAVLink message ID;
MAV_CMD_SET_MESSAGE_INTERVAL (#511, 0x01FF) * param1 = MAVLink message ID * param2 = interval between two messages, in microseconds; set to -1 to disable The periodic emission of one of these messages can be requested: * ATTITUDE (message id = 30) * MOUNT_STATUS (message id = 158) (target is set to broadcasting IDs) * MOUNT_ORIENTATION (message id = 265) Stream rates of up to 100 Hz are supported. Note however that this can take a significant toll and may strain the STorM32's microcontroller capabilities.
MAV_CMD_REQUEST_MESSAGE (#512, 0x0200) * param1 = message ID of the requested message 30: send ATTITUDE (message id = 30) 148: send AUTOPILOT_VERSION (message id = 148) 158: send MOUNT_STATUS (message id = 158) (target is set to the source IDs) 265: send MOUNT_ORIENTATION (message id = 265) 300: send PROTOCOL_VERSION (message id = 300) 700: send COMPONENT_INFORMATION (message id = 700)
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 4 Hz can be activated in the GUI via the Mavlink Gimbal Stream parameter, or by requesting a data stream using the MAV_CMD_SET_MESSAGE_INTERVAL command or a single-shot emission using MAV_CMD_REQUEST_MESSAGE.
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.
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 4 Hz can be activated in the GUI via the Mavlink Gimbal Stream parameter, and by requesting a data stream or single-shot emission with the MAV_CMD_SET_MESSAGE_INTERVAL or MAV_CMD_REQUEST_MESSAGE commands, respectively. The yaw angle is relative to the forward direction.
MAVLINK_MSG_ID_PROTOCOL_VERSION (#300, 0x12C)
See PROTOCOL_VERSION.
MAVLINK_MSG_ID_TUNNEL (#385, 0x181)
See TUNNEL.
The STorM32 controller occupies the block of payload_type values from 200 - 209 (see MAV_TUNNEL_PAYLOAD_TYPE). The payload types 200 and 201 are used for communicating with the GUI. Payload types 202 and 203 are for communicating with a flight controller, but can also be used otherwise.
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 component is independent on the MAVLink Gimbal component, and can also be used then the MAVLink Gimbal component is disabled.
The setting in the Mavlink Camera parameter enables the MAVLink Camera component, and determines its component ID: “Camera1” corresponds to MAV_COMP_ID_CAMERA (= 100), “Camera2” to MAV_COMP_ID_CAMERA2 (= 101), and so on. In addition, MAVLink 2 must be enabled; otherwise many functions of the MAVLink Camera component won't work properly:
- Mavlink Camera = “Camera1” or higher
- Mavlink Version = “Mavlink2”
The system ID of the MAVLink Camera component is determined by the parameter Mavlink System ID, which is also used by the MAVLink Gimbal component, and usually can be left at its default value.
The MAVLink Camera component supports the File Transfer Protocol micro service, which allows us to download the camera definition .xml files directly from the STorM32 gimbal controller.
The MAVLink Camera component is deeply related to the NT Camera. This means that it works in conjunction with the Camera Control function and associated parameters in the [GUI:Functions] tab.
Messages
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 (= 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_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_DIGICAM_CONTROL (#203, 0xCB) * param5 = shot (0 = off, 1 = SHUTTER)
MAV_CMD_REQUEST_MESSAGE (#512, 0x0200) * param1 = message ID of the requested message 148: send AUTOPILOT_VERSION message 259: send CAMERA_INFORMATION message 260: send CAMERA_SETTINGS message 261: send STORAGE_INFORMATION message 262: send CAMERA_CAPTURE_STATUS message 300: send PROTOCOL_VERSION message
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) returns COMMAND_ACK with MAV_CMD_ACK_DENIED
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (#527, 0x020F) send CAMERA_CAPTURE_STATUS message
MAV_CMD_RESET_CAMERA_SETTINGS (#529, 0x0211) returns COMMAND_ACK with MAV_CMD_ACK_DENIED
MAV_CMD_SET_CAMERA_MODE (#530, 0x0212) * param2 = camera mode
MAV_CMD_SET_CAMERA_ZOOM (#531, 0x0213) returns COMMAND_ACK with MAV_CMD_ACK_DENIED
MAV_CMD_SET_CAMERA_FOCUS (#532, 0x0214) returns COMMAND_ACK with MAV_CMD_ACK_DENIED
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) stops capturing images
MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE (#2002, 0x07D2) returns COMMAND_ACK with MAV_CMD_ACK_DENIED
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_FILE_TRANSFER_PROTOCOL (#110, 0x6E)
The opcodes TerminateSession, ResetSessions, ListDirectory, OpenFileRO, ReadFile and CalcFileCRC32 are supported.
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.