Serial Communication

From STorM32-BGC Wiki
Jump to navigation Jump to search

The information on this page refers to firmware v0.77a and higher.

Communication with the STorM32 board is possible through the serial interfaces USB, UART, and Bluetooth. Three sets of commands are available:

  • Serial Communication Protocol: This set has a very simple command structure, and is used for major tasks of the GUI.
  • Mavlink RC Commands: This set is targeted at a remote control of the STorM32 gimbal. It shares similarities with the Mavlink protocol, but isn't Mavlink.
  • Mavlink Commands: This set is "real" Mavlink.

Any command of each set can be processed through any of the serial interfaces (USB, UART, and Bluetooth). However, the Mavlink heartbeat is, when activated, emitted only through the UART, and Bluetooth.

Serial Communication Protocol

This protocol for the communication via the serial interfaces follows these rules:

  • The board responds to incoming commands by sending back a data stream of one or more characters, which is determined by the received command.
  • The board is never sending/transmitting anything by itself, that is, a transmission is always started only as a reaction to an incoming command.
  • The board is responding to any incoming command, be it valid or not.

Any data stream returned by the board ends with one of these characters:

  • 'o': indicates that everything is ok, i.e. that the received command has been identified
  • 'e': indicates that an error has occurred, i.e. that an invalid command has been received
  • 't': indicates that a timeout has occurred, i.e. that a command which consists of several characters was not completed within a certain time window
  • 'c': indicates that a checksum error has occurred

A checksum is invoked only for few commands, currently the 'p','g', and 'd' commands. The reason is that a checksum is certainly desirable from a security point of view, but quite inconvenient for hands-on communication via terminals etc., which is useful for development.

Command 't'

This command simply returns the character 'o'. Can be used by the host to check if the board is still connected.

Command 'v'

This command returns information on the installed firmware version, the name of the board, and the type of the board. The data stream is appended by a crc, and closed with the character 'o'.

Command 'g'

This command returns a data stream containing all parameter values. The data stream is appended by a crc, and closed with the character 'o'.

Command 'p'

This command sets all parameter values. The command character 'p' needs to be followed by a data stream containing all parameter values, plus a crc. It returns the character 'o'.

Command 'd'

Upon receipt of the command 'd' a data stream containing the current live data is transmitted. The live data is appended by a crc, and closed with the character 'o'. The respective C code snippet is as follows:

 //send 32 data values
 uart_prepare_transmit();
 ((u16*)fbuf)[(*len)++]= STATE; //state
 ((u16*)fbuf)[(*len)++]= status; //status
 ((u16*)fbuf)[(*len)++]= status2; //status2
 ((u16*)fbuf)[(*len)++]= i2c_geterrorcntofdevice(IMU_I2CDEVNR)+i2c_geterrorcntofdevice(IMU2_I2CDEVNR);
 ((u16*)fbuf)[(*len)++]= adc_lipovoltage(); //lipo_voltage;
 ((u16*)fbuf)[(*len)++]= (u16)systicks; //timestamp
 ((u16*)fbuf)[(*len)++]= (u16)(1.0E6*fdT); //cycle time
 ((u16*)fbuf)[(*len)++]= (s16)(fImu1.imu.gx);
 ((u16*)fbuf)[(*len)++]= (s16)(fImu1.imu.gy);
 ((u16*)fbuf)[(*len)++]= (s16)(fImu1.imu.gz);
 ((u16*)fbuf)[(*len)++]= (s16)(10000.0f*fImu1.imu.ax);
 ((u16*)fbuf)[(*len)++]= (s16)(10000.0f*fImu1.imu.ay);
 ((u16*)fbuf)[(*len)++]= (s16)(10000.0f*fImu1.imu.az);
 ((u16*)fbuf)[(*len)++]= (s16)(10000.0f*fImu1AHRS.R.x);
 ((u16*)fbuf)[(*len)++]= (s16)(10000.0f*fImu1AHRS.R.y);
 ((u16*)fbuf)[(*len)++]= (s16)(10000.0f*fImu1AHRS.R.z);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fImu1Angle.Pitch);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fImu1Angle.Roll);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fImu1Angle.Yaw);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*cPID[PITCH].Cntrl);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*cPID[ROLL].Cntrl);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*cPID[YAW].Cntrl);
 ((u16*)fbuf)[(*len)++]= InputSrc.Pitch;
 ((u16*)fbuf)[(*len)++]= InputSrc.Roll;
 ((u16*)fbuf)[(*len)++]= InputSrc.Yaw;
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fImu2Angle.Pitch);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fImu2Angle.Roll);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fImu2Angle.Yaw);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fMag2Angle.Yaw);
 ((u16*)fbuf)[(*len)++]= (s16)(100.0f*fMag2Angle.Pitch);
 ((u16*)fbuf)[(*len)++]= (s16)(10000.0f*fImu1AHRS._imu_acc_confidence);
 ((u16*)fbuf)[(*len)++] = pack_functioninputvalues(&FunctionInputPulse);
 (*len)*=2;
 //add crc
 uint16_t crc= do_crc( fbuf, fbuf_len );
 fbuf[fbuf_len++]= (u8)crc; //low byte
 fbuf[fbuf_len++]= (u8)(crc>>8); //high byte
 //end character
 uart_transmit_ackchar( closewith ); //this sends a 'o'

Command 's'

Upon receipt of the command 's' a data stream containing the current status data is transmitted. The data stream is appended by a crc, and closed with the character 'o'. The command is essentially identical to the 'd' command, except that it transmits only the first five data values.

Checksum

The checksum for protecting some data streams is the x25 16-bit crc used by Mavlink. C code can be found here.

Mavlink RC Communication

In addition to the serial commands described in the previous section, the o323bgc firmware also understands some "Mavlink"-type messages, which are intended for remote control of the gimbal. These messages are not real Mavlink messages in the sense that they would work in a Mavlink environment, but use the Mavlink data packet structure, with a modified start byte of 0xFD. This set of commands shall be referred to as "Mavlink RC" commands.

The rules of the communication are as before, the STorM32 controller emits a message only upon request, but never by itself, and any received message is acknowledged by a message send to the host. For messages from the host to the controller the SystemID is 'R' (= 0x52) and for messages from the controller to the host it is 'G' (= 0x47). The ComponentID is 'C' (= 0x43) in both cases.

The following commands can be send to the STorM32 controller:

CMD_GETVERSION (#1)

0xFD 0x00 0x00 0x52 0x43 0x01 crc-low-byte crc-high-byte

If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the firmware version, the setup layout version and board capabilities in this format will be emitted:

0xFD 0x06 0x00 0x47 0x43 0x00 data1-low data1-high data2-low data2-high data3-low data3-high crc-low-byte crc-high-byte

Data1 is the firmware version, data2 the setup layout version, and data3 holds the board capabilities value.

CMD_GETVERSIONSTR (#2)

0xFD 0x00 0x00 0x52 0x43 0x02 crc-low-byte crc-high-byte

If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the version string, name string and board string in this format will be emitted:

0xFD 0x30 0x00 0x47 0x43 0x02 data-stream crc-low-byte crc-high-byte

The data stream contains the 16 bytes version string, the 16 bytes name string and the 16 bytes board string.

CMD_GETPARAMETER (#3)

0xFD 0x02 0x00 0x52 0x43 0x03 data-low-byte data-high-byte crc-low-byte crc-high-byte

The data is of type uint16_t and represents the number of the parameter which is requested. If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the parameter value in this format will be emitted:

0xFD 0x04 0x00 0x47 0x43 0x03 data1-low-byte data1-high-byte data2-low-byte data2-high-byte crc-low-byte crc-high-byte

Data1 is the parameter number and data2 holds the parameter value.

CMD_SETPARAMETER (#4)

0xFD 0x04 0x00 0x52 0x43 0x04 data1-low-byte data1-high-byte data2-low-byte data2-high-byte crc-low-byte crc-high-byte

Data1 is the parameter number and data2 holds the parameter value. As response to this command a CMD_ACK message will be emitted.

CMD_GETDATA (#5)

0xFD 0x01 0x00 0x52 0x43 0x05 type-byte crc-low-byte crc-high-byte

Type specifies the type of the requested data stream; currently only type 0 is supported. If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the data stream in this format will be emitted:

0xFD 0x4A 0x00 0x47 0x43 0x05 type-byte 0x00 data-stream crc-low-byte crc-high-byte

The data stream contains the same data as send by the 'd' command.

CMD_GETDATAFIELD (#6)

0xFD 0x02 0x00 0x52 0x43 0x06 data-low-byte data-high-byte crc-low-byte crc-high-byte

The data is of type uint16_t and represents the number of the data field which is requested. If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the parameter value in this format will be emitted:

0xFD 0x04 0x00 0x47 0x43 0x06 data1-low-byte data1-high-byte data2-low-byte data2-high-byte crc-low-byte crc-high-byte

Data1 is the data field number and data2 holds the data field value.

CMD_SETPITCH (#10)

0xFD 0x02 0x00 0x52 0x43 0x0A data-low-byte data-high-byte crc-low-byte crc-high-byte

The data is of type uint16_t and can assume the values 700...2300. If the value 0 is send, then the pitch axis will be recentered. Any other values are ignored. As response to this command a CMD_ACK message will be emitted.

CMD_SETROLL (#11)

0xFD 0x02 0x00 0x52 0x43 0x0B data-low-byte data-high-byte crc-low-byte crc-high-byte

The data is of type uint16_t and can assume the values 700...2300. If the value 0 is send, then the roll axis will be recentered. Any other values are ignored. As response to this command a CMD_ACK message will be emitted.

CMD_SETYAW (#12)

0xFD 0x02 0x00 0x52 0x43 0x0C data-low-byte data-high-byte crc-low-byte crc-high-byte

The data is of type uint16_t and can assume the values 700...2300. If the value 0 is send, then the yaw axis will be recentered. Any other values are ignored. As response to this command a CMD_ACK message will be emitted.

CMD_SETPANMODE (#13)

0xFD 0x01 0x00 0x52 0x43 0x0D data-byte crc-low-byte crc-high-byte

The data is of type uint8_t and can assume these values: 0 = off, 1 = HOLDHOLDPAN, 2 = HOLDHOLDHOLD, 3 = PANPANPAN, 4 = PANHOLDHOLD, 5 = PANHOLDPAN. As response to this command a CMD_ACK message will be emitted.

CMD_SETSTANDBY(#14)

0xFD 0x01 0x00 0x52 0x43 0x0E data-byte crc-low-byte crc-high-byte

The data is of type uint8_t and can assume these values: 0 = off, 1 = on. As response to this command a CMD_ACK message will be emitted.

CMD_DOCAMERA(#15)

0xFD 0x06 0x00 0x52 0x43 0x0F dummy-byte data-byte dummy-byte dummy-byte dummy-byte dummy-byte crc-low-byte crc-high-byte

The data is of type uint8_t and can assume these values: 0 = off, 1 = IRSHUTTER, 2 = IRSHUTTERDELAYED, 3 = IRVIDEOON, 4 = IRVIDEOOFF. As response to this command a CMD_ACK message will be emitted.

CMD_SETSCRIPTCONTROL (#16)

0xFD 0x02 0x00 0x52 0x43 0x10 data1-byte data2-byte crc-low-byte crc-high-byte

The data1 and data2 are of type uint8_t. Data1 is the number of the script and data2 can assume these values: 0 = off, 1 = CASE#DEFAULT, 2 = CASE#1, 3 = CASE#2, 4 = CASE#3. As response to this command a CMD_ACK message will be emitted.

CMD_SETANGLE (#17)

0xFD 0x0E 0x00 0x52 0x43 0x11 float1 float2 float3 flags-byte type-byte crc-low-byte crc-high-byte

The float1, float2, float3 fields represent 4 bytes each. They are of type float, and correspond to the pitch, roll, and yaw angles in degree. The flags byte allows to modify the behavior of the angle setting for each angle. It can be in the limited or unlimited mode. In limited mode the angle setting is subject to the RcMin and RcMax settings, and works only for "absolute". In unlimited mode any angle value can be set without restriction, bypassing the RcMin and RcMax settings, and works for both "relative" and "absolute". The first bit, 0x01, corresponds to pitch, 0x02 to roll, and 0x04 to yaw, and when set the respective axis is in limited mode. The type byte is not used currently and has to be set to zero. As response to this command a CMD_ACK message will be emitted.

CMD_SETPITCHROLLYAW (#18)

0xFD 0x06 0x00 0x52 0x43 0x12 data1-low-byte data1-high-byte data2-low-byte data2-high-byte data3-low-byte data3-high-byte crc-low-byte crc-high-byte

The data1, data2 and data3 are each of type uint16_t and can assume the values 700...2300. They represent the pitch, roll, yaw input values. If a value 0 is send, then the respective axis will be recentered. Any other values are ignored. As response to this command a CMD_ACK message will be emitted.

CMD_SETPWMOUT (#19)

0xFD 0x02 0x00 0x52 0x43 0x13 data-low-byte data-high-byte crc-low-byte crc-high-byte

The data is of type uint16_t and can assume the values 1000...2000. As response to this command a CMD_ACK message will be emitted.

CMD_ACTIVEPANMODESETTING (#100)

0xFD 0x01 0x00 0x52 0x43 0x64 data-byte crc-low-byte crc-high-byte

The data is of type uint8_t and is a bit field related to the pan mode setting: default setting = 0x00, setting #1 = 0x01, setting #2 = 0x02, setting #3 = 0x03. As response to this command a CMD_ACK message will be emitted.

CMD_ACK (#150)

0xFD 0x01 0x00 0x47 0x43 0x96 data-byte crc-low-byte crc-high-byte

This command is returned by the STorM32 controller to acknowledge execution of a received message (if the message itself doesn't lead to a response, such as get parameter command). The data is of type uint8_t and can assume these values:

0 = MAV_CMD_ACK_OK=0

1 = MAV_CMD_ACK_ERR_FAIL

2 = MAV_CMD_ACK_ERR_ACCESS_DENIED

3 = MAV_CMD_ACK_ERR_NOT_SUPPORTED

150 = MAV_CMD_ACK_ERR_TIMEOUT

151 = MAV_CMD_ACK_ERR_CRC

152 = MAV_CMD_ACK_ERR_PAYLOADLEN

Mavlink Communication

In addition to the commands described in the previous sections, the o323bgc firmware also understands "real" Mavlink messages, as defined in the Mavlink standard. The implemented Mavlink commands are described in the mavlink_storm32.xml file.

The system ID and component ID can be freely adjusted; the defaults are

  • System ID: 'G' (= 71 = 0x47)
  • Component ID: 'C' (= 67 = 0x43)

The following commands are supported:

MAVLINK_MSG_ID_HEARTBEAT (#0)

See HEARTBEAT. The emission of the heartbeat needs to be activated. It is emitted at 1 Hz, with the following values:

  • type: MAV_TYPE_GIMBAL (= 26)
  • autopilot: 'S' (= 83 = 0x53) (may become MAV_AUTOPILOT_STORM32)
  • base_mode: 0
  • custom_mode: STATE value of the o323firmware
  • system_status: is either MAV_STATE_BOOT (= 1) or MAV_STATE_ACTIVE (= 4)

MAVLINK_MSG_ID_PARAM_REQUEST_READ (#20)

See PARAM_REQUEST_READ.

MAVLINK_MSG_ID_PARAM_REQUEST_LIST (#21)

See PARAM_REQUEST_LIST.

MAVLINK_MSG_ID_PARAM_VALUE (#22)

See PARAM_VALUE.

MAVLINK_MSG_ID_PARAM_SET (#23)

See PARAM_SET.

MAVLINK_MSG_ID_COMMAND_LONG (#76)

See COMMAND_LONG. These commands are supported:

* MAV_CMD_DO_SET_PARAMETER (#180)
*: param1 = parameter index (uint16_t)
*: param2 = parameter value (type depends on parameter)
*: param3 = not used
*: param4 = not used
*: param5 = not used
*: param6 = not used
*: param7 = not used
* MAV_CMD_DO_SET_SERVO (#183)
*: param1 = not used
*: param2 = pwm value (only 700...2300 accepted)
*: param3 = not used
*: param4 = not used
*: param5 = not used
*: param6 = not used
*: param7 = not used
* MAV_CMD_DO_DIGICAM_CONTROL (#203)
*: param1 = not used
*: param2 = not used
*: param3 = not used
*: param4 = not used
*: param5 = shot (0 = off, 1 = IRSHUTTER, 2 = IRSHUTTERDELAYED, 3 = IRVIDEOON, 4 = IRVIDEOOFF)
*: param6 = not used
*: param7 = not used

http://www.olliw.eu/storm32bgc-wiki/index.php?title=Serial_Communication&action=edit&section=16

* MAV_CMD_DO_MOUNT_CONTROL (#205)
*: param1 = pitch, angle in degree or pwm input, see CMD_SETPITCH (float)
*: param2 = roll, angle in degree or pwm input (float)
*: param3 = yaw, angle in degree or pwm input (float)
*: param4 = not used
*: param5 = not used
*: param6 = typeflags (uint16_t)
     0x0100: set pwm input instead of angle input
     0x0001: set limited range for pitch axis, see CMD_SETANGLE
     0x0002: set limited range for roll axis, see CMD_SETANGLE
     0x0004: set limited range for roll axis, see CMD_SETANGLE
*: param7 = not used

MAVLINK_MSG_ID_COMMAND_ACK (#77)

See COMMAND_ACK.

MAVLINK_MSG_ID_DIGICAM_CONTROL (#155)

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* shot: 0 = off, 1 = IRSHUTTER, 2 = IRSHUTTERDELAYED, 3 = IRVIDEOON, 4 = IRVIDEOOFF (uint8_t)

All other fields are ignored.

MAVLINK_MSG_ID_MOUNT_CONFIGURE (#156)

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* mount_mode: MAV_MOUNT_MODE_NEUTRAL recenters camera (uint8_t)

All other fields are ignored.

MAVLINK_MSG_ID_MOUNT_CONTROL (#157)

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* input_a: pitch angle in 0.01° (int32_t)
* input_b: roll angle in 0.01° (int32_t)
* input_c: yaw angle in 0.01° (int32_t)
* save_position:  (uint8_t) 
   

All other fields are ignored.

MAVLINK_MSG_ID_COMMAND_TARGET_SPECIFIC (#234)

Container for target specific messages. See Comments to STorM32 specific Mavlink commands below.

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* specific_payload: Target specific message as payload, the size can be variable, as needed

MAVLINK_MSG_ID_COMMAND_TARGET_SPECIFIC_ACK (#235)

Container for a target specific responses. May be emitted by the target as response to a COMMAND_TARGET_SPECIFIC message. See Comments to STorM32 specific Mavlink commands below.

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* specific_payload: Target specific response as payload, the size can be variable, as needed

MAVLINK_MSG_ID_PARAM_READ2 (#236)

Requests reading the parameter with index param_index. The target should respond with a PARAM_VALUE2 message.

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* param_index: Parameter index (uint16_t)

MAVLINK_MSG_ID_PARAM_SET2 (#237)

Sets the parameter with index param_index to the value param_value. The target should respond with a PARAM_VALUE2 message to acknowledge.

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* param_index: Parameter index (uint16_t)
* param_value: Parameter value (type depends on parameter)
* param_type: parameter type, see the MAV_PARAM_TYPE enum for supported data types (uint8_t)

MAVLINK_MSG_ID_PARAM_VALUE2 (#238)

Sends the value of the parameter with index param_index.

* target_system: System ID (uint8_t)
* target_component: Component ID (uint8_t)
* param_index: Parameter index (uint16_t)
* param_value: Parameter value (type depends on parameter)
* param_type: Parameter type, see the MAV_PARAM_TYPE enum for supported data types (uint8_t)
* param_count: Total number of parameters (uint16_t)

Comments to STorM32 specific Mavlink commands

The set of commands PARAM_READ2, PARAM_SET2, and PARAM_VALUE2 are alternatives to the analogous original commands, using only the parameter index to identify a parameter. This minimizes bandwidth and required processing power.

Comment: These commands will be complemented by two commands PARAM_REQUEST_LIST2 and PARAM_FIELD2, which also are alternatives to the analogous original command, but will provide more detailed info on the parameters such as default value, min and max values, formating info and so on. This will allow to program much more usable GUIs.

A major addition are the commands COMMAND_TARGET_SPECIFIC and COMMAND_TARGET_SPECIFIC_ACK. They are in some way similar to the COMMAND_LONG and COMMAND_ACK message pair, but do not impose format restrictions on the payload, and allow also to send information back to the sender. This optimizes not only bandwidth but also establishes a very flexible method to send information, in both directions if needed. These commands could also be viewed as containers for data, those content isn't known by Mavlink. It becomes thus possible to establish a communication channel between two arbitrary devices, using a Mavlink channel.

These commands are intended for peer-to-peer communication. That is the System and Component IDs of the ACK message are the Target System and Target Component IDs of the sending message, and vice versa.

These two commands are however not fully conform with the Mavlink standard, which currently doesn't support variable payloads. Hence, most of the routines provided by Mavlink cannot be used, namely those which rely on the hardcoded length associated to a message. Also, any router, which handles the distribution of the Mavlink messages, should not rely on the hardcoded lengths (at least not for the two discussed commands). These points are an inconvenience, but not hard to realize in practice.

In the o323bgc firmware, these commands currently embed the Mavlink RC commands. That is, for instance, the command CMD_SETANGLE with value 1000 (= 0x03E8) can be transmitted in two ways:

  • It can be transmitted as described in the above, with the 0xFD start sign. The sent byte stream is then:
0xFD 0x02 0x00 0x52 0x43 0x0A 0xE8 0x03 0xCRCLOW 0xCRCHIGH

and the received ACK stream

0xFD 0x01 0x00 0x47 0x43 0x96 0x00 0x52 0xE9
  • Its message id and payload is embedded into the COMMAND_TARGET_SPECIFIC command, i.e. the message id and payload becomes the specific payload. The byte stream is then:
0xFE 0x05 0xXX 0x52 0x43 0xEA 0x47 0x43 0x0A 0xE8 0x03 0xCRCLOW 0xCRCHIGH

and the received ACK stream

0xFE 0x04 0xYY 0x47 0x43 0xEB 0x52 0x43 0x96 0x00 0xCRCLOW 0xCRCHIGH

This of course works for all Mavlink RC commands, and their responses.

Comment: In a future version also the simple serial commands will be embedded into the COMMAND_TARGET_SPECIFIC/COMMAND_TARGET_SPECIFIC_ACK pair, so that the full command set and functionality is available through Mavlink channel.