Serial Communication: Difference between revisions
(236 intermediate revisions by 2 users not shown) | |||
Line 1: | Line 1: | ||
''The information on this page refers to firmware | <span style="font-size:88%">''The information on this page refers to firmware v2.69a and higher.''</span> | ||
Communication with the STorM32 board is possible through the serial interfaces USB, UART, and Bluetooth. Three sets of commands are available: | Communication with the STorM32 board is possible through the serial interfaces USB, UART, and UART2 (Bluetooth and Wifi can be achieved by using corresponding dongles). Three sets of commands are available for serial communication: | ||
* | * '''''Simple Commands''''': This set has a very simple command structure, and is used for major tasks of the GUI. | ||
* | * '''''RC Commands''''': This set is targeted at a remote control of the STorM32 gimbal. | ||
* Mavlink Commands: This set is "real" | * '''''Mavlink Commands''''': This set is "real" MAVLink. | ||
Any command of | The simple and the RC commands share many similarities, and could be considered the two sides of a coin (they both are in fact processed by the same code part in the firmware). They tend to be more efficient than the MAVLink commands. Any command of any set can be processed through any of the serial interfaces. However, when the MAVLink Gimbal or MAVLink Camera component is activated, then the serial port selected for MAVLink accepts only MAVLink commands, and on v1.3x boards also Bluetooth may not be used anymore. | ||
The commands of each of the three command sets can be used interchangeably. The command set whih the command belongs to is determined by the first received character. This implies that in case of a communication error, the message parser may misinterpret characters which follow the error. The message parser is reset after a timeout. | |||
For understanding all details of the communication, it is generally best to peek into the source code of the GUI (which is included in any firmware package). It's written in Perl, and Perl is sufficiently primitive to understand the code easily. | |||
<div class="toclimit-2">__TOC__</div> | <div class="toclimit-2">__TOC__</div> | ||
== Serial Communication | == Serial Communication - Simple Commands == | ||
This protocol for the communication via the serial interfaces follows these rules: | This protocol for the communication via the serial interfaces follows these rules: | ||
Line 17: | Line 22: | ||
* The board is responding to '''any''' incoming command, be it valid or not. | * The board is responding to '''any''' incoming command, be it valid or not. | ||
Any data | Any data packet 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 | * '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 | * 'e': indicates that an error has occurred, i.e. that an invalid command has been received | ||
Line 23: | Line 28: | ||
* 'c': indicates that a checksum error has occurred | * 'c': indicates that a checksum error has occurred | ||
A checksum is invoked | A checksum is invoked whenever data are transmitted, as e.g. for the 'p','g', and 'd' commands. | ||
{{COMMENT|Only the most important simple commands are listed below. There are many more for interacting with the STorM32 controller; please inspect the GUI source code to identify them and their usage.}} | |||
=== Command 't' === | === Command 't' === | ||
Line 29: | Line 36: | ||
=== Command 'v' === | === Command 'v' === | ||
This command returns information on the installed firmware version, the name of the board, and the type of the board. The data | This command returns information on the installed firmware version, the name of the board, and the type of the board. The data packet is appended by a crc, and closed with the character 'o'. | ||
=== Command 'g' === | === Command 'g' === | ||
This command returns a data | This command returns a data packet containing all parameter values. The data packet is appended by a crc, and closed with the character 'o'. | ||
=== Command 'p' === | === Command 'p' === | ||
This command sets all parameter values. The command character 'p' needs to be followed by a data | This command sets all parameter values. The command character 'p' needs to be followed by a data packet containing all parameter values, plus a crc. It returns the character 'o'. | ||
=== Command 'd' === | === Command 'd' === | ||
Upon receipt of the command 'd' a data | Upon receipt of the command 'd' a data packet 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: | ||
// | uint8_t pos = 0; | ||
// LIVEDATA_STATUS_V2: | |||
((u16*) | ((u16*)buf)[pos++] = STATE; // state | ||
((u16*) | ((u16*)buf)[pos++] = status; // status | ||
((u16*) | ((u16*)buf)[pos++] = status2; // status2 | ||
((u16*) | ((u16*)buf)[pos++] = status3; // status3 | ||
((u16*) | ((u16*)buf)[pos++] = (s16)(Performance.MaxLoopdone*10); // performance | ||
((u16*) | ((u16*)buf)[pos++] = imu_ntbus_geterrocnt() + imu_onboard_geterrocnt(); // errors | ||
((u16*) | ((u16*)buf)[pos++] = lipo_voltage(); // lipo_voltage | ||
((u16*) | // LIVEDATA_TIMES: | ||
((u16*) | ((u16*)buf)[pos++] = (u16)looptime.millis_32; // timestamp | ||
((u16*) | ((u16*)buf)[pos++] = 0; // not used | ||
((u16*) | // LIVEDATA_IMU1GYRO: not included | ||
((u16*) | // LIVEDATA_IMU1ACC: not included | ||
((u16*) | // LIVEDATA_IMU1R: | ||
((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS.R.x); // Imu1 R estimates, in 0.0001 g | |||
((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS.R.y); | |||
((u16*) | ((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS.R.z); | ||
// LIVEDATA_IMU1ANGLES: | |||
((u16*)buf)[pos++] = (s16)(100*aImu1Angle.Pitch); // Imu1 angles, in 0.01° | |||
((u16*) | ((u16*)buf)[pos++] = (s16)(100*aImu1Angle.Roll); | ||
((u16*) | ((u16*)buf)[pos++] = (s16)(100*aImu1Angle.Yaw); | ||
((u16*) | // LIVEDATA_PIDCNTRL: | ||
((u16*) | if (IS_ENCODERS_ENABLED || (IS_IMU2_PRESENT && IS_IMU2_FULL && IS_3AXISGIMBAL)) { | ||
((u16*) | ((u16*)buf)[pos++] = (s16)(100*cPID[PITCH].Cntrl); // PID output, in 0.01° | ||
((u16*)buf)[pos++] = (s16)(100*cPID[ROLL].Cntrl); | |||
((u16*)buf)[pos++] = (s16)(100*cPID[YAW].Cntrl); | |||
((u16*) | } else { | ||
((u16*)buf)[pos++] = (s16)(100*cPID[PITCH].Cntrl - cPID[PITCH].SetPoint); // relative PID output, in 0.01° | |||
((u16*)buf)[pos++] = (s16)(100*cPID[ROLL].Cntrl - cPID[ROLL].SetPoint); | |||
((u16*) | ((u16*)buf)[pos++] = (s16)(100*cPID[YAW].Cntrl - cPID[YAW].SetPoint); | ||
((u16*) | } | ||
((u16*) | // LIVEDATA_INPUTS: | ||
((u16*) | ((u16*)buf)[pos++] = InputSrc.Pitch; // Rc Input values | ||
(* | ((u16*)buf)[pos++] = InputSrc.Roll; | ||
//add crc | ((u16*)buf)[pos++] = InputSrc.Yaw; | ||
uint16_t crc= do_crc( | // LIVEDATA_IMU2ANGLES: (these are the STorM32-Link angles when IS_STORM32LINK_INUSE) | ||
((u16*)buf)[pos++] = (s16)(100*aImu2Angle.Pitch); // Imu2 angles, in 0.01° | |||
((u16*)buf)[pos++] = (s16)(100*aImu2Angle.Roll); | |||
//end character | ((u16*)buf)[pos++] = (s16)(100*aImu2Angle.Yaw); | ||
uart_transmit_ackchar( closewith ); //this sends a 'o' | // LIVEDATA_ENCODERANGLES: | ||
if (IS_ENCODERS_ENABLED || IS_ENCODERS_PRESENT) { | |||
((u16*)buf)[pos++] = (s16)(100*motorfoc_aEncoderAngle(PITCH)); // Encoder angles, in 0.01° | |||
((u16*)buf)[pos++] = (s16)(100*motorfoc_aEncoderAngle(ROLL)); | |||
((u16*)buf)[pos++] = (s16)(100*motorfoc_aEncoderAngle(YAW)); | |||
} else { | |||
((u16*)buf)[pos++] = (s16)(100*cPID[PITCH].MotorCntrl); // Motor angles, in 0.01° | |||
((u16*)buf)[pos++] = (s16)(100*cPID[ROLL].MotorCntrl); | |||
((u16*)buf)[pos++] = (s16)(100*cPID[YAW].MotorCntrl); | |||
} | |||
// LIVEDATA_STORM32LINK: | |||
((u16*)buf)[pos++] = (s16)(100*toR1earthYaw(aImu1Angle.Yaw)); // Imu1 yaw angle in earth frame, in 0.01° | |||
((u16*)buf)[pos++] = (s16)(100*getR2earthYaw()); // yaw angle from flight controller, in 0.01° | |||
// LIVEDATA_IMUACCSTATS: | |||
((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS._acc_magnitude); | |||
((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS._acc_confidence); | |||
// LIVEDATA_STORM32LINK 2nd part: | |||
((u16*)buf)[pos++] = debug; | |||
// LIVEDATA_ATTITUDE_RELATIVE: not included | |||
pos *= 2; | |||
// add crc | |||
uint16_t crc = do_crc(buf, pos); | |||
buf[pos++] = (u8)crc; // low byte | |||
buf[pos++] = (u8)(crc >> 8); // high byte | |||
// end character | |||
uart_transmit_ackchar(closewith); // this sends the data and a 'o' | |||
=== Command 's' === | === Command 's' === | ||
Upon receipt of the command 's' a data | Upon receipt of the command 's' a data packet containing the current status data is transmitted. The data packet 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 seven data values. | ||
=== Checksum === | === Checksum === | ||
The checksum for protecting some data | The checksum for protecting some data packets is the x25 16-bit crc used by [https://mavlink.io/en/ MAVLink]. C code can be found [https://github.com/olliw42/fastmavlink/blob/master/c_library/lib/fastmavlink_crc.h here]. | ||
== | == Serial Communication - RC Commands == | ||
The rules of the communication are as before | In addition to the simple serial commands described in the previous section, the STorM32 controller also understands some messages targeted at remote control of the gimbal. These messages have a stricter data format, and provide a higher level of transmission reliability. They also provide a much richer command set and allow access to STorM32's full potential. | ||
The rules of the communication are exactly as before: | |||
* The STorM32 board emits a message only upon request, but never by itself. | |||
* Any received message is acknowledged by a message send back to the host. | |||
The general structure of a data frame is: | |||
* Startsign: 0xFA for incoming messages, and 0xFB for outgoing messages | |||
* Length: length of the payload, i.e. number of bytes of the data packet excluding<br> Start sign, Length byte, Command byte, and crc word | |||
* Command: the command byte | |||
* Payload: as many bytes as expected by the command | |||
* Checksum: x25 16-bit crc excluding start byte, as used by [https://mavlink.io/en/ MAVLink]; C code can be found [https://github.com/olliw42/fastmavlink/blob/master/c_library/lib/fastmavlink_crc.h here] | |||
{{COMMENT|The response can be suppressed by using a 0xF9 start sign, instead of a 0xFA.}} | |||
The following commands can be send to the STorM32 controller: | The following commands can be send to the STorM32 controller: | ||
==== CMD_GETVERSION (#1) ==== | ==== CMD_GETVERSION (#1) ==== | ||
0xFA 0x00 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: | 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: | ||
0xFB 0x06 0x01 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. | Data1 is the firmware version, data2 the setup layout version, and data3 holds the board capabilities value. | ||
==== CMD_GETVERSIONSTR (#2) ==== | ==== CMD_GETVERSIONSTR (#2) ==== | ||
0xFA 0x00 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: | 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: | ||
0xFB 0x30 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. | The data stream contains the 16 bytes version string, the 16 bytes name string and the 16 bytes board string. | ||
==== CMD_GETPARAMETER (#3) ==== | ==== CMD_GETPARAMETER (#3) ==== | ||
0xFA 0x02 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: | 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: | ||
0xFB 0x04 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. | Data1 is the parameter number and data2 holds the parameter value. | ||
==== CMD_SETPARAMETER (#4) ==== | ==== CMD_SETPARAMETER (#4) ==== | ||
0xFA 0x04 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. | 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) ==== | ==== CMD_GETDATA (#5) ==== | ||
0xFA 0x01 0x05 type-byte crc-low-byte crc-high-byte | |||
Type specifies the type of the requested data | Type specifies the type of the requested data; currently only type 0 is supported. If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the data in this format will be emitted: | ||
0xFB 0x4A 0x05 type-byte 0x00 data-stream crc-low-byte crc-high-byte | |||
Data-stream holds the data, which is the same data as send by the 'd' command. | |||
The data | ==== CMD_GETDATAFIELDS (#6) ==== | ||
0xFA 0x02 0x06 bitmask-low-byte bitmask-high-byte crc-low-byte crc-high-byte | |||
The bitmask is of type uint16_t and represents a bitmask to specify which data should be send. If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the bitmask word and all the requested data in this format will be emitted: | |||
0xFB LEN 0x06 bitmask-low-byte bitmask-high-byte data-stream crc-low-byte crc-high-byte | |||
Bitmask is the bitmask word, and data-stream holds the corresponding data. The following bits can be set: | |||
0x0002 = LIVEDATA_TIMES | |||
0x0004 = LIVEDATA_IMU1GYRO | |||
0x0008 = LIVEDATA_IMU1ACC | |||
0x0010 = LIVEDATA_IMU1R | |||
0x0020 = LIVEDATA_IMU1ANGLES | |||
0x0040 = LIVEDATA_PIDCNTRL | |||
0x0080 = LIVEDATA_INPUTS | |||
0x0100 = LIVEDATA_IMU2ANGLES | |||
0x0400 = LIVEDATA_STORM32LINK | |||
0x0800 = LIVEDATA_IMUACCSTATS | |||
0x1000 = LIVEDATA_ATTITUDE_RELATIVE | |||
0x2000 = LIVEDATA_STATUS_V2 | |||
0x4000 = LIVEDATA_ENCODERANGLES | |||
Note that the order of the flags does not coincide with the order of the respective data in the data-stream; the order in data-stream can be read off from the documentation for the 'd' command. The data send in the 'd' and CMD_GETDATA commands correspond to the bitmask | |||
LIVEDATA_STATUS_V2 | LIVEDATA_TIMES | LIVEDATA_IMU1R | LIVEDATA_IMU1ANGLES | LIVEDATA_PIDCNTRL | \ | |||
LIVEDATA_INPUTS | LIVEDATA_IMU2ANGLES | LIVEDATA_ENCODERANGLES | LIVEDATA_STORM32LINK | LIVEDATA_IMUACCSTATS | |||
{{COMMENT|The flags have slightly changed in v2.61, so are slightly different in older firmware versions.}} | |||
==== CMD_SETPITCH (#10) ==== | ==== CMD_SETPITCH (#10) ==== | ||
0xFA 0x02 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. | The data is of type uint16_t and can assume the values 700...2300. It represents the pitch input value. 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) ==== | ==== CMD_SETROLL (#11) ==== | ||
0xFA 0x02 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. | The data is of type uint16_t and can assume the values 700...2300. It represents the roll input value. 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) ==== | ==== CMD_SETYAW (#12) ==== | ||
0xFA 0x02 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. | The data is of type uint16_t and can assume the values 700...2300. It represents the yaw input value. 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) ==== | ==== CMD_SETPANMODE (#13) ==== | ||
0xFA 0x01 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. | The data is of type uint8_t and can assume these values: 0 = off, 1 = HOLDHOLDPAN, 2 = HOLDHOLDHOLD, 3 = PANPANPAN, 4 = PANHOLDHOLD, 5 = PANHOLDPAN, 6 = HOLDPANPAN. As response to this command a CMD_ACK message will be emitted. | ||
==== CMD_SETSTANDBY(#14) ==== | ==== CMD_SETSTANDBY(#14) ==== | ||
0xFA 0x01 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. | 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) ==== | ==== CMD_DOCAMERA(#15) ==== | ||
0xFA 0x06 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 = | The data is of type uint8_t and can assume these values: 0 = off, 1 = SHUTTER, 2 = SHUTTERDELAYED, 3 = VIDEOON, 4 = VIDEOOFF. As response to this command a CMD_ACK message will be emitted. | ||
==== CMD_SETSCRIPTCONTROL (#16) ==== | ==== CMD_SETSCRIPTCONTROL (#16) ==== | ||
0xFA 0x02 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. | The data1 and data2 are of type uint8_t. Data1 is the number of the script (0 = scritp1, 1 = script2, etc) and data2 can assume these values: 0 = off, 1 = CASE#DEFAULT, 2 = CASE#1, 3 = CASE#2, 4 = CASE#3, 5 = CASE#4. As response to this command a CMD_ACK message will be emitted. | ||
==== | ==== CMD_SETANGLES (#17) ==== | ||
0xFA 0x0E 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 | 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 and type bytes are not used and have to be set to zero. As response to this command a CMD_ACK message will be emitted. {{COMMENT|In previous firmware versions the flags byte allowed to set the behavior of the angle setting for each axis to unlimited or limited mode. The behavior now corresponds to flags 0, or unlimited mode for all axes.}} <!--The flags byte allows to modify the behavior of the angle setting for each axis. They can be in the unlimited or limited mode. In unlimited mode the respective axis can be set to any angle without restriction, bypassing the {{PARAMNAME|RcMin}} and {{PARAMNAME|RcMax}} settings, and working for both {{PARAMVALUE|relative}} and {{PARAMVALUE|absolute}}. In limited mode the angle setting is subject to the {{PARAMNAME|RcMin}} and {{PARAMNAME|RcMax}} settings, and works only for {{PARAMVALUE|absolute}}. The first bit of the flags byte, 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) ==== | ==== CMD_SETPITCHROLLYAW (#18) ==== | ||
0xFA 0x06 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. | 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) ==== | ==== CMD_SETPWMOUT (#19) ==== | ||
0xFA 0x02 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 700...2300. As response to this command a CMD_ACK message will be emitted. | The data is of type uint16_t and can assume the values 700...2300. It represents the pwm pass through input value. As response to this command a CMD_ACK message will be emitted. | ||
==== | ==== CMD_RESTOREPARAMETER (#20) ==== | ||
0xFA 0x02 0x14 data-low-byte data-high-byte crc-low-byte crc-high-byte | |||
The data is of type | The data is of type uint16_t and holds the parameter number. This command sets the parameter to the value in the EEPROM. As response to this command a CMD_ACK message will be emitted. | ||
==== | ==== CMD_RESTOREALLPARAMETER (#21) ==== | ||
0xFA 0x00 0x15 crc-low-byte crc-high-byte | |||
This command | This command sets all parameters to the values stored in the EEPROM. As response to this command a CMD_ACK message will be emitted. | ||
==== CMD_SETINPUTS (#22) ==== | |||
0xFA 0x17 0x16 data-bytes crc-low-byte crc-high-byte | |||
This overwrites the data received from virtual inputs, if {{PARAMNAME|Virtual Channel Configuration}} = {{PARAMVALUE|serial}} is configured. The data bytes are formatted similarly to sbus: 16 channels of 11 bit values combined into 22 bytes, plus a status byte. The range is 0...2047, and 1500 equals center. As response to this command a CMD_ACK message will be emitted. | |||
==== CMD_SETHOMELOCATION (#23) ==== | |||
Deprecated. | |||
==== CMD_SETTARGETLOCATION (#24) ==== | |||
Deprecated. | |||
==== CMD_SETINPUTCHANNEL (#25) ==== | |||
0xFA 0x04 0x19 data1-low data1-high data2-low data2-high crc-low-byte crc-high-byte | |||
This overwrites the data received from virtual inputs for the specified channel, if {{PARAMNAME|Virtual Channel Configuration}} = {{PARAMVALUE|serial}} is configured. The data1 and data2 are of type uint16_t each. Data1 is the channel number. Data2 is the channel value, the range is 700...2300, and 1500 equals center. As response to this command a CMD_ACK message will be emitted. | |||
==== CMD_SETCAMERA (#26) ==== | |||
0xFA 0x04 0x1A data1-low data1-high data2-low data2-high crc-low-byte crc-high-byte | |||
The data1 and data2 are of type uint16_t each, and can assume the values 700...2300, and 1500 equals center. If the value 0 is send, then the respective input is cleared. Any other values are ignored. Data1 and data2 represent the camera control and camera control2 input values, respectively. As response to this command a CMD_ACK message will be emitted. | |||
==== CMD_SENDCAMERACOMMAND (#27) ==== | |||
0xFA 0x01-0x12 0x1B data1 ... data24 crc-low-byte crc-high-byte | |||
The data1 to data18 are of type uint8_t. The message can have 1 to 24 of them, i.e., length byte can vary from 0x01 to 0x12. The data are send to the NT Camera uart port. As response to this command a CMD_ACK message will be emitted. | |||
==== CMD_SETANGLES_UNRESTRICTED (#28) ==== | |||
0xFA 0x18 0x1C float1 float2 float3 float4 float5 float6 crc-low-byte crc-high-byte | |||
The float1 - float6 fields represent 4 bytes each. They are of type float. Float1, float2, float3 correspond to the desired pitch, roll, and yaw angles in degrees. Float4, float5, float6 correspond to the desired pitch rate, roll rate, and yaw rate in degrees per second (only positive values are admitted). A value of zero means that no rate is applied. {{COMMENT|The rates are not the components of the angular velocity vector, but indeed the rates of the respective angles.}} As response to this command a CMD_ACK message will be emitted. | |||
== | ==== CMD_SETRETRACT(#29) ==== | ||
0xFA 0x01 0x1D 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. | |||
The | ==== CMD_ACTIVEPANMODESETTING (#100) ==== | ||
0xFA 0x01 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) ==== | |||
0xFB 0x01 0x96 data-byte crc-low-byte crc-high-byte | |||
This command is send by the STorM32 controller to acknowledge execution of a received RC command message (if the message itself doesn't lead to a response, such as e.g. the get parameter command). The data is of type uint8_t and can assume these values: | |||
0 = SERIALRCCMD_ACK_OK | |||
1 = SERIALRCCMD_ACK_ERR_FAIL | |||
2 = SERIALRCCMD_ACK_ERR_ACCESS_DENIED | |||
3 = SERIALRCCMD_ACK_ERR_NOT_SUPPORTED | |||
150 = SERIALRCCMD_ACK_ERR_TIMEOUT | |||
151 = SERIALRCCMD_ACK_ERR_CRC | |||
152 = SERIALRCCMD_ACK_ERR_PAYLOADLEN | |||
==== | ==== CMD_CONNECT (#210) ==== | ||
Deprecated. | |||
==== CMD_GETDATADISPLAY (#213) ==== | |||
Deprecated. | |||
==== | ==== CMD_WIFICONNECTEDPING (#215) ==== | ||
Deprecated. | |||
==== CMD_STORM32LINK_V1 (#217) ==== | |||
Deprecated. | |||
==== | ==== CMD_STORM32LINK_V2 (#218) ==== | ||
Special command: Is used for transmitting from a flight controller to the STorM32 for the STorM32-Link. | |||
== Mavlink Communication == | |||
In addition to the commands described in the previous sections, the STorM32 controller also understands MAVLink messages, as defined in the [https://mavlink.io/en/ MAVLink] standard. The STorM32 controller's MAVLink support is in fact quite rich, and quite complex, and actually provides two MAVLink components. Therefore, the description is placed in a separate article [[MAVLink Communication]]. | |||
The STorM32's MAVLink Gimbal component is enabled by opening the {{GUI|Interfaces Tool}} window, which is accessible via the {{GUI|Tools}} menu, and setting {{PARAMNAME|Mavlink Gimbal}} to {{PARAMVALUE|Gimbal1}}, which also sets the component ID. For further details see [[MAVLink Communication]]. | |||
<!-- | |||
== Comments on STorM32 specific Mavlink Messages == | |||
==== | ==== COMMAND_LONG - MAV_CMD_GET_ATTITUDE ==== | ||
The command MAV_CMD_GET_ATTITUDE is deprecated, but still existing for compatibility reasons. The command triggered the emission of a [http://mavlink.org/messages/common#ATTITUDE ATTITUDE] message instead of a [http://mavlink.org/messages/common#COMMAND_ACK COMMAND_ACK] message. This allowed to ask for the gimbal attitude whenever it is required. The command should be replaced by using either the MAVLINK_MSG_ID_MESSAGE_INTERVAL message or a corresponding MAV_CMD_TARGET_SPECIFIC command. | |||
==== | ==== COMMAND_LONG - MAV_CMD_TARGET_SPECIFIC ==== | ||
The command MAV_CMD_TARGET_SPECIFIC was added. This command can be viewed as a container to transmit data, those content isn't known to MAVLink. It thus becomes possible to establish a communication between two arbitrary devices, using a MAVLink channel. The command is intended for peer-to-peer communication, but of course is handled like any other COMMAND_LONG message by the MAVLink systems. The working principle is to treat the memory space of the seven param fields as a contiguous data buffer of 28 bytes, which hosts the target specific message. Obviously, only target specific messages of lengths less or equal 28 bytes can be handled. | |||
In the o323bgc firmware, the command is used to embed both the simple serial and RC commands. That is, the param memory space hosts the serial or RC command, with the crc bytes stripped off however since the message is already crc protected by MAVLink. | |||
For instance, the command CMD_SETPITCH with value 1000 (= 0x03E8) can be transmitted in two ways from a MAVLink device (with IDs 0xYY and 0xZZ) to the STorM32 controller (with IDs 0x47 and 0x43): | |||
* It can be transmitted as described in the above, with the 0xFA start sign. The byte stream which is sent to the STorM32 controller is then: | |||
0xFA 0x02 0x0A 0xE8 0x03 CRCLOW CRCHIGH | |||
and the received ACK stream is: | |||
0xFB 0x01 0x96 0x00 0x52 0xE9 | |||
* The message can be embedded into the MAV_CMD_TARGET_SPECIFIC command, i.e. the param field space becomes the target specific message, without its crc. The byte stream is then: | |||
0xFE 0x21 0xXX 0xYY 0xZZ 0x4C 0xFA 0x02 0x0A 0xE8 0x03 23*0x00 0xD3 0x04 0x47 0x43 0x00 CRCLOW CRCHIGH | |||
and the received ACK stream is: | |||
0xFE 0x21 0xXX 0x47 0x43 0x4C 0xFB 0x01 0x96 0x00 24*0x00 0xD3 0x04 0xYY 0xZZ 0x00 CRCLOW CRCHIGH | |||
This of course works for all serial and RC commands, and their responses. Thus, the full command set and functionality of the STorM32 controller is available through MAVLink channels. --><!-- | |||
==== | ==== PARAM_READ2, PARAM_SET2, PARAM_VALUE2 ==== | ||
== | |||
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. | 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. | ||
Line 361: | Line 356: | ||
{{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.}} | {{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 | ==== COMMAND_TARGET_SPECIFIC, COMMAND_TARGET_SPECIFIC_ACK ==== | ||
A major addition are the commands COMMAND_TARGET_SPECIFIC and COMMAND_TARGET_SPECIFIC_ACK. They are in some way similar to the pair of messages COMMAND_LONG and COMMAND_ACK, 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 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, | These two commands are however not fully conform with the Mavlink standard, which currently doesn't support variable payloads. Hence, all routines provided by Mavlink which rely on the hardcoded length associated to a message cannot be used. 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 however quite easy to realize in practice. | ||
In the o323bgc firmware, these commands | In the o323bgc firmware, these commands allow to embed both the simple serial and the 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 | * It can be transmitted as described in the above, with the 0xFA start sign. The sent byte stream is then: | ||
0xFA 0x02 0x11 0xE8 0x03 CRCLOW CRCHIGH | |||
and the received ACK stream | and the received ACK stream | ||
0xFB 0x01 0x96 0x00 0x52 0xE9 | |||
* | * The message can be 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 | 0xFE 0x05 0xXX 0xYY 0xZZ 0xEA 0x47 0x43 0xFA 0x11 0xE8 0x03 CRCLOW CRCHIGH | ||
and the received ACK stream | and the received ACK stream | ||
0xFE 0x04 0xYY 0x47 0x43 0xEB | 0xFE 0x04 0xYY 0x47 0x43 0xEB 0xYY 0xZZ 0x96 0x00 CRCLOW CRCHIGH | ||
This of course works for all serial commands, and their responses. Thus, the full command set and functionality is available through Mavlink channel. --> | |||
== Code Examples == | |||
Please see [[Code_Examples#Serial_Communication|Code Examples: Serial Communication]]. |
Latest revision as of 20:21, 16 January 2024
The information on this page refers to firmware v2.69a and higher.
Communication with the STorM32 board is possible through the serial interfaces USB, UART, and UART2 (Bluetooth and Wifi can be achieved by using corresponding dongles). Three sets of commands are available for serial communication:
- Simple Commands: This set has a very simple command structure, and is used for major tasks of the GUI.
- RC Commands: This set is targeted at a remote control of the STorM32 gimbal.
- Mavlink Commands: This set is "real" MAVLink.
The simple and the RC commands share many similarities, and could be considered the two sides of a coin (they both are in fact processed by the same code part in the firmware). They tend to be more efficient than the MAVLink commands. Any command of any set can be processed through any of the serial interfaces. However, when the MAVLink Gimbal or MAVLink Camera component is activated, then the serial port selected for MAVLink accepts only MAVLink commands, and on v1.3x boards also Bluetooth may not be used anymore.
The commands of each of the three command sets can be used interchangeably. The command set whih the command belongs to is determined by the first received character. This implies that in case of a communication error, the message parser may misinterpret characters which follow the error. The message parser is reset after a timeout.
For understanding all details of the communication, it is generally best to peek into the source code of the GUI (which is included in any firmware package). It's written in Perl, and Perl is sufficiently primitive to understand the code easily.
Serial Communication - Simple Commands
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 packet 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 whenever data are transmitted, as e.g. for the 'p','g', and 'd' commands.
Comment: Only the most important simple commands are listed below. There are many more for interacting with the STorM32 controller; please inspect the GUI source code to identify them and their usage.
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 packet is appended by a crc, and closed with the character 'o'.
Command 'g'
This command returns a data packet containing all parameter values. The data packet 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 packet containing all parameter values, plus a crc. It returns the character 'o'.
Command 'd'
Upon receipt of the command 'd' a data packet 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:
uint8_t pos = 0; // LIVEDATA_STATUS_V2: ((u16*)buf)[pos++] = STATE; // state ((u16*)buf)[pos++] = status; // status ((u16*)buf)[pos++] = status2; // status2 ((u16*)buf)[pos++] = status3; // status3 ((u16*)buf)[pos++] = (s16)(Performance.MaxLoopdone*10); // performance ((u16*)buf)[pos++] = imu_ntbus_geterrocnt() + imu_onboard_geterrocnt(); // errors ((u16*)buf)[pos++] = lipo_voltage(); // lipo_voltage // LIVEDATA_TIMES: ((u16*)buf)[pos++] = (u16)looptime.millis_32; // timestamp ((u16*)buf)[pos++] = 0; // not used // LIVEDATA_IMU1GYRO: not included // LIVEDATA_IMU1ACC: not included // LIVEDATA_IMU1R: ((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS.R.x); // Imu1 R estimates, in 0.0001 g ((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS.R.y); ((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS.R.z); // LIVEDATA_IMU1ANGLES: ((u16*)buf)[pos++] = (s16)(100*aImu1Angle.Pitch); // Imu1 angles, in 0.01° ((u16*)buf)[pos++] = (s16)(100*aImu1Angle.Roll); ((u16*)buf)[pos++] = (s16)(100*aImu1Angle.Yaw); // LIVEDATA_PIDCNTRL: if (IS_ENCODERS_ENABLED || (IS_IMU2_PRESENT && IS_IMU2_FULL && IS_3AXISGIMBAL)) { ((u16*)buf)[pos++] = (s16)(100*cPID[PITCH].Cntrl); // PID output, in 0.01° ((u16*)buf)[pos++] = (s16)(100*cPID[ROLL].Cntrl); ((u16*)buf)[pos++] = (s16)(100*cPID[YAW].Cntrl); } else { ((u16*)buf)[pos++] = (s16)(100*cPID[PITCH].Cntrl - cPID[PITCH].SetPoint); // relative PID output, in 0.01° ((u16*)buf)[pos++] = (s16)(100*cPID[ROLL].Cntrl - cPID[ROLL].SetPoint); ((u16*)buf)[pos++] = (s16)(100*cPID[YAW].Cntrl - cPID[YAW].SetPoint); } // LIVEDATA_INPUTS: ((u16*)buf)[pos++] = InputSrc.Pitch; // Rc Input values ((u16*)buf)[pos++] = InputSrc.Roll; ((u16*)buf)[pos++] = InputSrc.Yaw; // LIVEDATA_IMU2ANGLES: (these are the STorM32-Link angles when IS_STORM32LINK_INUSE) ((u16*)buf)[pos++] = (s16)(100*aImu2Angle.Pitch); // Imu2 angles, in 0.01° ((u16*)buf)[pos++] = (s16)(100*aImu2Angle.Roll); ((u16*)buf)[pos++] = (s16)(100*aImu2Angle.Yaw); // LIVEDATA_ENCODERANGLES: if (IS_ENCODERS_ENABLED || IS_ENCODERS_PRESENT) { ((u16*)buf)[pos++] = (s16)(100*motorfoc_aEncoderAngle(PITCH)); // Encoder angles, in 0.01° ((u16*)buf)[pos++] = (s16)(100*motorfoc_aEncoderAngle(ROLL)); ((u16*)buf)[pos++] = (s16)(100*motorfoc_aEncoderAngle(YAW)); } else { ((u16*)buf)[pos++] = (s16)(100*cPID[PITCH].MotorCntrl); // Motor angles, in 0.01° ((u16*)buf)[pos++] = (s16)(100*cPID[ROLL].MotorCntrl); ((u16*)buf)[pos++] = (s16)(100*cPID[YAW].MotorCntrl); } // LIVEDATA_STORM32LINK: ((u16*)buf)[pos++] = (s16)(100*toR1earthYaw(aImu1Angle.Yaw)); // Imu1 yaw angle in earth frame, in 0.01° ((u16*)buf)[pos++] = (s16)(100*getR2earthYaw()); // yaw angle from flight controller, in 0.01° // LIVEDATA_IMUACCSTATS: ((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS._acc_magnitude); ((u16*)buf)[pos++] = (s16)(10000*Imu1AHRS._acc_confidence); // LIVEDATA_STORM32LINK 2nd part: ((u16*)buf)[pos++] = debug; // LIVEDATA_ATTITUDE_RELATIVE: not included pos *= 2; // add crc uint16_t crc = do_crc(buf, pos); buf[pos++] = (u8)crc; // low byte buf[pos++] = (u8)(crc >> 8); // high byte // end character uart_transmit_ackchar(closewith); // this sends the data and a 'o'
Command 's'
Upon receipt of the command 's' a data packet containing the current status data is transmitted. The data packet 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 seven data values.
Checksum
The checksum for protecting some data packets is the x25 16-bit crc used by MAVLink. C code can be found here.
Serial Communication - RC Commands
In addition to the simple serial commands described in the previous section, the STorM32 controller also understands some messages targeted at remote control of the gimbal. These messages have a stricter data format, and provide a higher level of transmission reliability. They also provide a much richer command set and allow access to STorM32's full potential.
The rules of the communication are exactly as before:
- The STorM32 board emits a message only upon request, but never by itself.
- Any received message is acknowledged by a message send back to the host.
The general structure of a data frame is:
* Startsign: 0xFA for incoming messages, and 0xFB for outgoing messages * Length: length of the payload, i.e. number of bytes of the data packet excluding
Start sign, Length byte, Command byte, and crc word * Command: the command byte * Payload: as many bytes as expected by the command * Checksum: x25 16-bit crc excluding start byte, as used by MAVLink; C code can be found here
Comment: The response can be suppressed by using a 0xF9 start sign, instead of a 0xFA.
The following commands can be send to the STorM32 controller:
CMD_GETVERSION (#1)
0xFA 0x00 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:
0xFB 0x06 0x01 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)
0xFA 0x00 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:
0xFB 0x30 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)
0xFA 0x02 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:
0xFB 0x04 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)
0xFA 0x04 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)
0xFA 0x01 0x05 type-byte crc-low-byte crc-high-byte
Type specifies the type of the requested data; currently only type 0 is supported. If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the data in this format will be emitted:
0xFB 0x4A 0x05 type-byte 0x00 data-stream crc-low-byte crc-high-byte
Data-stream holds the data, which is the same data as send by the 'd' command.
CMD_GETDATAFIELDS (#6)
0xFA 0x02 0x06 bitmask-low-byte bitmask-high-byte crc-low-byte crc-high-byte
The bitmask is of type uint16_t and represents a bitmask to specify which data should be send. If an error occurred a CMD_ACK message will be emitted. Otherwise a message containing the bitmask word and all the requested data in this format will be emitted:
0xFB LEN 0x06 bitmask-low-byte bitmask-high-byte data-stream crc-low-byte crc-high-byte
Bitmask is the bitmask word, and data-stream holds the corresponding data. The following bits can be set:
0x0002 = LIVEDATA_TIMES 0x0004 = LIVEDATA_IMU1GYRO 0x0008 = LIVEDATA_IMU1ACC 0x0010 = LIVEDATA_IMU1R 0x0020 = LIVEDATA_IMU1ANGLES 0x0040 = LIVEDATA_PIDCNTRL 0x0080 = LIVEDATA_INPUTS 0x0100 = LIVEDATA_IMU2ANGLES 0x0400 = LIVEDATA_STORM32LINK 0x0800 = LIVEDATA_IMUACCSTATS 0x1000 = LIVEDATA_ATTITUDE_RELATIVE 0x2000 = LIVEDATA_STATUS_V2 0x4000 = LIVEDATA_ENCODERANGLES
Note that the order of the flags does not coincide with the order of the respective data in the data-stream; the order in data-stream can be read off from the documentation for the 'd' command. The data send in the 'd' and CMD_GETDATA commands correspond to the bitmask
LIVEDATA_STATUS_V2 | LIVEDATA_TIMES | LIVEDATA_IMU1R | LIVEDATA_IMU1ANGLES | LIVEDATA_PIDCNTRL | \ LIVEDATA_INPUTS | LIVEDATA_IMU2ANGLES | LIVEDATA_ENCODERANGLES | LIVEDATA_STORM32LINK | LIVEDATA_IMUACCSTATS
Comment: The flags have slightly changed in v2.61, so are slightly different in older firmware versions.
CMD_SETPITCH (#10)
0xFA 0x02 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. It represents the pitch input value. 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)
0xFA 0x02 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. It represents the roll input value. 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)
0xFA 0x02 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. It represents the yaw input value. 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)
0xFA 0x01 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, 6 = HOLDPANPAN. As response to this command a CMD_ACK message will be emitted.
CMD_SETSTANDBY(#14)
0xFA 0x01 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)
0xFA 0x06 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 = SHUTTER, 2 = SHUTTERDELAYED, 3 = VIDEOON, 4 = VIDEOOFF. As response to this command a CMD_ACK message will be emitted.
CMD_SETSCRIPTCONTROL (#16)
0xFA 0x02 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 (0 = scritp1, 1 = script2, etc) and data2 can assume these values: 0 = off, 1 = CASE#DEFAULT, 2 = CASE#1, 3 = CASE#2, 4 = CASE#3, 5 = CASE#4. As response to this command a CMD_ACK message will be emitted.
CMD_SETANGLES (#17)
0xFA 0x0E 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 and type bytes are not used and have to be set to zero. As response to this command a CMD_ACK message will be emitted. Comment: In previous firmware versions the flags byte allowed to set the behavior of the angle setting for each axis to unlimited or limited mode. The behavior now corresponds to flags 0, or unlimited mode for all axes.
CMD_SETPITCHROLLYAW (#18)
0xFA 0x06 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)
0xFA 0x02 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 700...2300. It represents the pwm pass through input value. As response to this command a CMD_ACK message will be emitted.
CMD_RESTOREPARAMETER (#20)
0xFA 0x02 0x14 data-low-byte data-high-byte crc-low-byte crc-high-byte
The data is of type uint16_t and holds the parameter number. This command sets the parameter to the value in the EEPROM. As response to this command a CMD_ACK message will be emitted.
CMD_RESTOREALLPARAMETER (#21)
0xFA 0x00 0x15 crc-low-byte crc-high-byte
This command sets all parameters to the values stored in the EEPROM. As response to this command a CMD_ACK message will be emitted.
CMD_SETINPUTS (#22)
0xFA 0x17 0x16 data-bytes crc-low-byte crc-high-byte
This overwrites the data received from virtual inputs, if Virtual Channel Configuration = “serial” is configured. The data bytes are formatted similarly to sbus: 16 channels of 11 bit values combined into 22 bytes, plus a status byte. The range is 0...2047, and 1500 equals center. As response to this command a CMD_ACK message will be emitted.
CMD_SETHOMELOCATION (#23)
Deprecated.
CMD_SETTARGETLOCATION (#24)
Deprecated.
CMD_SETINPUTCHANNEL (#25)
0xFA 0x04 0x19 data1-low data1-high data2-low data2-high crc-low-byte crc-high-byte
This overwrites the data received from virtual inputs for the specified channel, if Virtual Channel Configuration = “serial” is configured. The data1 and data2 are of type uint16_t each. Data1 is the channel number. Data2 is the channel value, the range is 700...2300, and 1500 equals center. As response to this command a CMD_ACK message will be emitted.
CMD_SETCAMERA (#26)
0xFA 0x04 0x1A data1-low data1-high data2-low data2-high crc-low-byte crc-high-byte
The data1 and data2 are of type uint16_t each, and can assume the values 700...2300, and 1500 equals center. If the value 0 is send, then the respective input is cleared. Any other values are ignored. Data1 and data2 represent the camera control and camera control2 input values, respectively. As response to this command a CMD_ACK message will be emitted.
CMD_SENDCAMERACOMMAND (#27)
0xFA 0x01-0x12 0x1B data1 ... data24 crc-low-byte crc-high-byte
The data1 to data18 are of type uint8_t. The message can have 1 to 24 of them, i.e., length byte can vary from 0x01 to 0x12. The data are send to the NT Camera uart port. As response to this command a CMD_ACK message will be emitted.
CMD_SETANGLES_UNRESTRICTED (#28)
0xFA 0x18 0x1C float1 float2 float3 float4 float5 float6 crc-low-byte crc-high-byte
The float1 - float6 fields represent 4 bytes each. They are of type float. Float1, float2, float3 correspond to the desired pitch, roll, and yaw angles in degrees. Float4, float5, float6 correspond to the desired pitch rate, roll rate, and yaw rate in degrees per second (only positive values are admitted). A value of zero means that no rate is applied. Comment: The rates are not the components of the angular velocity vector, but indeed the rates of the respective angles. As response to this command a CMD_ACK message will be emitted.
CMD_SETRETRACT(#29)
0xFA 0x01 0x1D 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_ACTIVEPANMODESETTING (#100)
0xFA 0x01 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)
0xFB 0x01 0x96 data-byte crc-low-byte crc-high-byte
This command is send by the STorM32 controller to acknowledge execution of a received RC command message (if the message itself doesn't lead to a response, such as e.g. the get parameter command). The data is of type uint8_t and can assume these values:
0 = SERIALRCCMD_ACK_OK 1 = SERIALRCCMD_ACK_ERR_FAIL 2 = SERIALRCCMD_ACK_ERR_ACCESS_DENIED 3 = SERIALRCCMD_ACK_ERR_NOT_SUPPORTED 150 = SERIALRCCMD_ACK_ERR_TIMEOUT 151 = SERIALRCCMD_ACK_ERR_CRC 152 = SERIALRCCMD_ACK_ERR_PAYLOADLEN
CMD_CONNECT (#210)
Deprecated.
CMD_GETDATADISPLAY (#213)
Deprecated.
CMD_WIFICONNECTEDPING (#215)
Deprecated.
CMD_STORM32LINK_V1 (#217)
Deprecated.
CMD_STORM32LINK_V2 (#218)
Special command: Is used for transmitting from a flight controller to the STorM32 for the STorM32-Link.
Mavlink Communication
In addition to the commands described in the previous sections, the STorM32 controller also understands MAVLink messages, as defined in the MAVLink standard. The STorM32 controller's MAVLink support is in fact quite rich, and quite complex, and actually provides two MAVLink components. Therefore, the description is placed in a separate article MAVLink Communication.
The STorM32's MAVLink Gimbal component is enabled by opening the [GUI:Interfaces Tool] window, which is accessible via the [GUI:Tools] menu, and setting Mavlink Gimbal to “Gimbal1”, which also sets the component ID. For further details see MAVLink Communication.
Code Examples
Please see Code Examples: Serial Communication.