CyberAtom X-201 User Manual

Request Messages

Table 1. List of UART request messages.
Message Message ID (hex) Description
GET_SYS_INFO 0x01 Requests sending back information on the device type and firmware version.
GET_QUAT_DATA 0x02 Requests sending back actual orientation in quaternion representation.
GET_EULER_DATA 0x03 Requests sending back actual orientation in Euler angles representation.
GET_ROT_RATE_DATA 0x04 Requests sending back actual rotation rates.
REBOOT 0x05 Reboots the device.
FACTORY_RESET 0x07 Brings factory defaults settings to device RAM.
SET_ACC_CALIB_MAT 0x08 Sends calbration matrices for the accelerometer sensor.
SET_MAG_CALIB_MAT 0x09 Sends calbration matrices for the magnetometer sensor.
SET_GYR_CALIB_MAT 0x0A Sends calbration matrices for the gyrosope sensor.
SET_FILTER_MAG 0x0B Sends new values for measurement filter magnetometer matrix.
SET_FILTER_ACC 0x0C Sends new values for measurement filter accelerometer matrix.
SET_FILTER_GYR 0x0D Sends new values for measurement filter gyroscope matrix.
SET_FILTER_PROCN 0x0E Sends new values for filter process noise matrix.
GET_TEMP 0x0F Requests sending current temperature reading
SET_BAUD_RATE 0x10 Requests changing UART interface baud rate. Newly applied baud rate will be used after next power-on or reset of the device. To make sure they persist, WRITE_FLASH command should be used afterwards.
SET_I2C_ADDR 0x11 Requests changing I2C slave address. Newly applied I2C slave address will be after next power-on or reset of the device. To make sure they persist, WRITE_FLASH command should be used afterwards.
RESET_GYR 0x15 Resets actual gyroscope settings (only in RAM) treating current rotation as bias only (not rotating device).
WRITE_FLASH 0x16 Saves current settings to device Flash for persistance. Once written, these settings will be available after next power-on.
GET_ACC_CALIB_MAT 0x17 Requests sending back actual accelometer calibration settings.
GET_MAG_CALIB_MAT 0x18 Requests sending back actual magnetometer calibration settings.
GET_GYR_CALIB_MAT 0x19 Requests sending back actual gyeroscope calibration settings.
GET_RAW_ACC 0x20 Requests sending raw accelerometer measurement data.
GET_RAW_MAG 0x21 Requests sending raw magnetometer measurement data.
GET_RAW_GYR 0x22 Requests sending raw gyroscope measurement data.
GET_NORM_ACC 0x23 Requests sending normalized accelerometer measurement data.
GET_NORM_MAG 0x24 Requests sending normalized magnetometer measurement data.
GET_NORM_GYR 0x25 Requests sending normalized gyroscope measurement data.
GET_CALIB_ACC 0x26 Requests sending calibrated accelerometer measurement data.
GET_CALIB_MAG 0x27 Requests sending calibrated magnetometer measurement data.
GET_CALIB_GYR 0x28 Requests sending calibrated gyroscope measurement data.
REBOOT_BOOTLOADER 0x29 Requests rebooting to the bootloader mode
GET_FILTER_MAG 0x2B Requests values for measurement filter magnetometer matrix.
GET_FILTER_ACC 0x2C Requests values for measurement filter accelerometer matrix.
GET_FILTER_GYR 0x2D Requests values for measurement filter gyroscope matrix.
GET_FILTER_PROCN 0x2E Requests values for filter process noise matrix.
GET_I2C_ADDR 0x30 Requests currently set I2C address.
GET_BAUD_RATE 0x31 Requests currently set baud rate.

GET_SYS_INFO

Message ID: 0x01

Description: Requests sending back information on the device type and firmware version.

Message size: 6 bytes

When device receives this message, it will reply with sending back SYS_INFO message.

Table 2. Structure of complete GET_SYS_INFO message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x01 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0D9 Checksum byte.

GET_QUAT_DATA

Message ID: 0x02

Description: Requests sending back actual orientation in quaternion representation.

Message size: 6 bytes

When device receives this message, it will reply with sending back QUAT_DATA message.

Table 3. Structure of complete GET_QUAT_DATA message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x02 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0DA Checksum byte.

GET_EULER_DATA

Message ID: 0x03

Description: Requests sending back actual orientation in Euler angles representation.

Message size: 6 bytes

When device receives this message, it will reply with sending back EULER_DATA message.

Table 4. Structure of complete GET_EULER_DATA message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x03 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0DB Checksum byte.

GET_ROT_RATE_DATA

Message ID: 0x04

Description: Requests sending back actual rotation rates.

Message size: 6 bytes

When device receives this message, it will reply with sending back ROT_RATE_DATA message.

Table 5. Structure of complete GET_ROT_RATE_DATA message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x04 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0DC Checksum byte.

REBOOT

Message ID: 0x05

Description: Reboots the device.

Message size: 6 bytes

Table 6. Structure of complete REBOOT message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x05 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0DD Checksum byte.

FACTORY_RESET

Message ID: 0x07

Description: Brings factory defaults settings to device RAM.

Message size: 6 bytes

Table 7. Structure of complete FACTORY_RESET message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x07 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0DF Checksum byte.

SET_ACC_CALIB_MAT

Message ID: 0x08

Description: Sends calbration matrices for the accelerometer sensor.

Message size: 78 bytes

When device receives this message, it will reply with sending back CONFIRM message.

Table 8. Structure of complete SET_ACC_CALIB_MAT message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x08 Message ID.
3 16-bit unsigned 0x048 Number of bytes in payload.
5 IEEE754 float (varies) c11 matrix component
9 IEEE754 float (varies) c12 matrix component
13 IEEE754 float (varies) c13 matrix component
17 IEEE754 float (varies) c21 matrix component
21 IEEE754 float (varies) c22 matrix component
25 IEEE754 float (varies) c23 matrix component
29 IEEE754 float (varies) c31 matrix component
33 IEEE754 float (varies) c32 matrix component
37 IEEE754 float (varies) c33 matrix component
41 IEEE754 float (varies) t11 matrix component
45 IEEE754 float (varies) t12 matrix component
49 IEEE754 float (varies) t13 matrix component
53 IEEE754 float (varies) t21 matrix component
57 IEEE754 float (varies) t22 matrix component
61 IEEE754 float (varies) t23 matrix component
65 IEEE754 float (varies) t31 matrix component
69 IEEE754 float (varies) t32 matrix component
73 IEEE754 float (varies) t33 matrix component
77 8-bit unsigned (varies) Checksum byte.

SET_MAG_CALIB_MAT

Message ID: 0x09

Description: Sends calbration matrices for the magnetometer sensor.

Message size: 78 bytes

When device receives this message, it will reply with sending back CONFIRM message.

Table 9. Structure of complete SET_MAG_CALIB_MAT message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x09 Message ID.
3 16-bit unsigned 0x048 Number of bytes in payload.
5 IEEE754 float (varies) c11 matrix component
9 IEEE754 float (varies) c12 matrix component
13 IEEE754 float (varies) c13 matrix component
17 IEEE754 float (varies) c21 matrix component
21 IEEE754 float (varies) c22 matrix component
25 IEEE754 float (varies) c23 matrix component
29 IEEE754 float (varies) c31 matrix component
33 IEEE754 float (varies) c32 matrix component
37 IEEE754 float (varies) c33 matrix component
41 IEEE754 float (varies) t11 matrix component
45 IEEE754 float (varies) t12 matrix component
49 IEEE754 float (varies) t13 matrix component
53 IEEE754 float (varies) t21 matrix component
57 IEEE754 float (varies) t22 matrix component
61 IEEE754 float (varies) t23 matrix component
65 IEEE754 float (varies) t31 matrix component
69 IEEE754 float (varies) t32 matrix component
73 IEEE754 float (varies) t33 matrix component
77 8-bit unsigned (varies) Checksum byte.

SET_GYR_CALIB_MAT

Message ID: 0x0A

Description: Sends calbration matrices for the gyrosope sensor.

Message size: 78 bytes

When device receives this message, it will reply with sending back CONFIRM message.

Table 10. Structure of complete SET_GYR_CALIB_MAT message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x0A Message ID.
3 16-bit unsigned 0x048 Number of bytes in payload.
5 IEEE754 float (varies) c11 matrix component
9 IEEE754 float (varies) c12 matrix component
13 IEEE754 float (varies) c13 matrix component
17 IEEE754 float (varies) c21 matrix component
21 IEEE754 float (varies) c22 matrix component
25 IEEE754 float (varies) c23 matrix component
29 IEEE754 float (varies) c31 matrix component
33 IEEE754 float (varies) c32 matrix component
37 IEEE754 float (varies) c33 matrix component
41 IEEE754 float (varies) t11 matrix component
45 IEEE754 float (varies) t12 matrix component
49 IEEE754 float (varies) t13 matrix component
53 IEEE754 float (varies) t21 matrix component
57 IEEE754 float (varies) t22 matrix component
61 IEEE754 float (varies) t23 matrix component
65 IEEE754 float (varies) t31 matrix component
69 IEEE754 float (varies) t32 matrix component
73 IEEE754 float (varies) t33 matrix component
77 8-bit unsigned (varies) Checksum byte.

SET_FILTER_MAG

Message ID: 0x0B

Description: Sends new values for measurement filter magnetometer matrix.

Message size: 18 bytes

When device receives this message, it will reply with sending back CONFIRM message.

Table 11. Structure of complete SET_FILTER_MAG message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x0B Message ID.
3 16-bit unsigned 0x0C Number of bytes in payload.
5 IEEE754 float (varies) h11 matrix component
9 IEEE754 float (varies) h22 matrix component
13 IEEE754 float (varies) h33 matrix component
17 8-bit unsigned (varies) Checksum byte.

SET_FILTER_ACC

Message ID: 0x0C

Description: Sends new values for measurement filter accelerometer matrix.

Message size: 18 bytes

When device receives this message, it will reply with sending back CONFIRM message.

Table 12. Structure of complete SET_FILTER_ACC message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x0C Message ID.
3 16-bit unsigned 0x0C Number of bytes in payload.
5 IEEE754 float (varies) h11 matrix component
9 IEEE754 float (varies) h22 matrix component
13 IEEE754 float (varies) h33 matrix component
17 8-bit unsigned (varies) Checksum byte.

SET_FILTER_GYR

Message ID: 0x0D

Description: Sends new values for measurement filter gyroscope matrix.

Message size: 18 bytes

When device receives this message, it will reply with sending back CONFIRM message.

Table 13. Structure of complete SET_FILTER_GYR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x0D Message ID.
3 16-bit unsigned 0x0C Number of bytes in payload.
5 IEEE754 float (varies) h11 matrix component
9 IEEE754 float (varies) h22 matrix component
13 IEEE754 float (varies) h33 matrix component
17 8-bit unsigned (varies) Checksum byte.

SET_FILTER_PROCN

Message ID: 0x0E

Description: Sends new values for filter process noise matrix.

Message size: 34 bytes

When device receives this message, it will reply with sending back CONFIRM message.

Table 14. Structure of complete SET_FILTER_PROCN message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x0E Message ID.
3 16-bit unsigned 0x01C Number of bytes in payload.
5 IEEE754 float (varies) q11 matrix component
9 IEEE754 float (varies) q22 matrix component
13 IEEE754 float (varies) q33 matrix component
17 IEEE754 float (varies) q44 matrix component
21 IEEE754 float (varies) q55 matrix component
25 IEEE754 float (varies) q66 matrix component
29 IEEE754 float (varies) q77 matrix component
33 8-bit unsigned (varies) Checksum byte.

GET_TEMP

Message ID: 0x0F

Description: Requests sending current temperature reading

Message size: 6 bytes

When device receives this message, it will reply with sending back TEMP message.

Table 15. Structure of complete GET_TEMP message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x0F Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0E7 Checksum byte.

SET_BAUD_RATE

Message ID: 0x10

Description: Requests changing UART interface baud rate. Newly applied baud rate will be used after next power-on or reset of the device. To make sure they persist, WRITE_FLASH command should be used afterwards.

Message size: 7 bytes

When device receives this message, it will reply with sending back BAUD_RATE message.

Table 16. Structure of complete SET_BAUD_RATE message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x10 Message ID.
3 16-bit unsigned 0x01 Number of bytes in payload.
5 8-bit unsigned (varies) New baud rate. One of the following values:

0x01 - 2400 bauds

0x02 - 4800 bauds

0x03 - 9600 bauds

0x04 - 19200 bauds

0x05 - 38400 bauds

0x06 - 57600 bauds

0x07 - 115200 bauds

0x08 - 230400 bauds

0x09 - 576000 bauds

0x0A - 921600 bauds

6 8-bit unsigned (varies) Checksum byte.

SET_I2C_ADDR

Message ID: 0x11

Description: Requests changing I2C slave address. Newly applied I2C slave address will be after next power-on or reset of the device. To make sure they persist, WRITE_FLASH command should be used afterwards.

Message size: 7 bytes

When device receives this message, it will reply with sending back I2C_ADDR message.

Table 17. Structure of complete SET_I2C_ADDR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x11 Message ID.
3 16-bit unsigned 0x01 Number of bytes in payload.
5 8-bit unsigned (varies) New 7-bit I2C slave address for the device.
6 8-bit unsigned (varies) Checksum byte.

RESET_GYR

Message ID: 0x15

Description: Resets actual gyroscope settings (only in RAM) treating current rotation as bias only (not rotating device).

Message size: 6 bytes

Table 18. Structure of complete RESET_GYR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x15 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0ED Checksum byte.

WRITE_FLASH

Message ID: 0x16

Description: Saves current settings to device Flash for persistance. Once written, these settings will be available after next power-on.

Message size: 6 bytes

Table 19. Structure of complete WRITE_FLASH message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x16 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0EE Checksum byte.

GET_ACC_CALIB_MAT

Message ID: 0x17

Description: Requests sending back actual accelometer calibration settings.

Message size: 6 bytes

When device receives this message, it will reply with sending back ACC_CALIB_MAT message.

Table 20. Structure of complete GET_ACC_CALIB_MAT message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x17 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0EF Checksum byte.

GET_MAG_CALIB_MAT

Message ID: 0x18

Description: Requests sending back actual magnetometer calibration settings.

Message size: 6 bytes

When device receives this message, it will reply with sending back MAG_CALIB_MAT message.

Table 21. Structure of complete GET_MAG_CALIB_MAT message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x18 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0F0 Checksum byte.

GET_GYR_CALIB_MAT

Message ID: 0x19

Description: Requests sending back actual gyeroscope calibration settings.

Message size: 6 bytes

When device receives this message, it will reply with sending back GYR_CALIB_MAT message.

Table 22. Structure of complete GET_GYR_CALIB_MAT message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x19 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0F1 Checksum byte.

GET_RAW_ACC

Message ID: 0x20

Description: Requests sending raw accelerometer measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back RAW_ACC message.

Table 23. Structure of complete GET_RAW_ACC message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x20 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0F8 Checksum byte.

GET_RAW_MAG

Message ID: 0x21

Description: Requests sending raw magnetometer measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back RAW_MAG message.

Table 24. Structure of complete GET_RAW_MAG message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x21 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0F9 Checksum byte.

GET_RAW_GYR

Message ID: 0x22

Description: Requests sending raw gyroscope measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back RAW_GYR message.

Table 25. Structure of complete GET_RAW_GYR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x22 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0FA Checksum byte.

GET_NORM_ACC

Message ID: 0x23

Description: Requests sending normalized accelerometer measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back NORM_ACC message.

Table 26. Structure of complete GET_NORM_ACC message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x23 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0FB Checksum byte.

GET_NORM_MAG

Message ID: 0x24

Description: Requests sending normalized magnetometer measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back NORM_MAG message.

Table 27. Structure of complete GET_NORM_MAG message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x24 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0FC Checksum byte.

GET_NORM_GYR

Message ID: 0x25

Description: Requests sending normalized gyroscope measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back NORM_GYR message.

Table 28. Structure of complete GET_NORM_GYR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x25 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0FD Checksum byte.

GET_CALIB_ACC

Message ID: 0x26

Description: Requests sending calibrated accelerometer measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back CALIB_ACC message.

Table 29. Structure of complete GET_CALIB_ACC message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x26 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0FE Checksum byte.

GET_CALIB_MAG

Message ID: 0x27

Description: Requests sending calibrated magnetometer measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back CALIB_MAG message.

Table 30. Structure of complete GET_CALIB_MAG message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x27 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x0FF Checksum byte.

GET_CALIB_GYR

Message ID: 0x28

Description: Requests sending calibrated gyroscope measurement data.

Message size: 6 bytes

When device receives this message, it will reply with sending back CALIB_GYR message.

Table 31. Structure of complete GET_CALIB_GYR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x28 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x00 Checksum byte.

REBOOT_BOOTLOADER

Message ID: 0x29

Description: Requests rebooting to the bootloader mode

Message size: 6 bytes

Table 32. Structure of complete REBOOT_BOOTLOADER message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x29 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x01 Checksum byte.

GET_FILTER_MAG

Message ID: 0x2B

Description: Requests values for measurement filter magnetometer matrix.

Message size: 6 bytes

When device receives this message, it will reply with sending back FILTER_MAG message.

Table 33. Structure of complete GET_FILTER_MAG message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x2B Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x03 Checksum byte.

GET_FILTER_ACC

Message ID: 0x2C

Description: Requests values for measurement filter accelerometer matrix.

Message size: 6 bytes

When device receives this message, it will reply with sending back FILTER_ACC message.

Table 34. Structure of complete GET_FILTER_ACC message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x2C Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x04 Checksum byte.

GET_FILTER_GYR

Message ID: 0x2D

Description: Requests values for measurement filter gyroscope matrix.

Message size: 6 bytes

When device receives this message, it will reply with sending back FILTER_GYR message.

Table 35. Structure of complete GET_FILTER_GYR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x2D Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x05 Checksum byte.

GET_FILTER_PROCN

Message ID: 0x2E

Description: Requests values for filter process noise matrix.

Message size: 6 bytes

When device receives this message, it will reply with sending back FILTER_PROCN message.

Table 36. Structure of complete GET_FILTER_PROCN message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x2E Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x06 Checksum byte.

GET_I2C_ADDR

Message ID: 0x30

Description: Requests currently set I2C address.

Message size: 6 bytes

When device receives this message, it will reply with sending back I2C_ADDR message.

Table 37. Structure of complete GET_I2C_ADDR message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x30 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x08 Checksum byte.

GET_BAUD_RATE

Message ID: 0x31

Description: Requests currently set baud rate.

Message size: 6 bytes

When device receives this message, it will reply with sending back BAUD_RATE message.

Table 38. Structure of complete GET_BAUD_RATE message on UART interface.
Byte Offset Data Type Value (hex) Descripion
0 8-bit unsigned 0x05 First header byte.
1 8-bit unsigned 0xD3 Second header byte.
2 8-bit unsigned 0x31 Message ID.
3 16-bit unsigned 0x00 Number of bytes in payload.
5 8-bit unsigned 0x09 Checksum byte.