Register Overview

Table of Contents

There are three types of registers onboard the UM7:

  1. configuration registers,

  2. data registers, and

  3. command registers.

Configuration registers begin at address 0x00 and are used to configure UM7’s filter settings and communication behavior. Configuration register contents can be written to onboard flash to allow settings to be maintained when the device is powered down.

Data registers begin at address 0x55 (85d), and store raw and processed data from the sensors along with estimated states. Unlike configuration registers, data register contents cannot be written to flash.

Command registers technically aren’t registers at all, but they provide a convenient way to send commands to the UM7 when those commands do not require additional data beyond the command itself. For example, a command to run an onboard gyro bias calibration routine is triggered by querying the ZERO_GYROS command register. By using a unique register address for each command, the same communication architecture used to read from and write to data and configuration registers can be used to send commands to the autopilot. Command registers begin at address 0xAA.

Configuration Registers

Table 17 Configuration Registers

Address

Register Name

Register Description

0x00 (0d)

CREG_COM_SETTINGS

General communication settings

0x01 (1d)

CREG_COM_RATES1

Broadcast rate settings

0x02 (2d)

CREG_COM_RATES2

Broadcast rate settings

0x03 (3d)

CREG_COM_RATES3

Broadcast rate settings

0x04 (4d)

CREG_COM_RATES4

Broadcast rate settings

0x05 (5d)

CREG_COM_RATES5

Broadcast rate settings

0x06 (6d)

CREG_COM_RATES6

Broadcast rate settings

0x07 (7d)

CREG_COM_RATES7

Broadcast rate settings

0x08 (8d)

CREG_MISC_SETTINGS

Misc. settings

0x09 (9d)

CREG_HOME_NORTH

GPS north position to consider position 0

0x0A (10d)

CREG_HOME_EAST

GPS east position to consider position 0

0x0B (11d)

CREG_HOME_UP

GPS altitude to consider position 0

0x0C (12d)

CREG_GYRO_TRIM_X

Bias trim for x-axis rate gyro

0x0D (13d)

CREG_GYRO_TRIM_Y

Bias trim for y-axis rate gyro

0x0E (14d)

CREG_GYRO_TRIM_Z

Bias trim for z-axis rate gyro

0x0F (15d)

CREG_MAG_CAL1_1

Row 1, Column 1 of magnetometer calibration matrix

0x10 (16d)

CREG_MAG_CAL1_2

Row 1, Column 2 of magnetometer calibration matrix

0x11 (17d)

CREG_MAG_CAL1_3

Row 1, Column 3 of magnetometer calibration matrix

0x12 (18d)

CREG_MAG_CAL2_1

Row 2, Column 1 of magnetometer calibration matrix

0x13 (19d)

CREG_MAG_CAL2_2

Row 2, Column 2 of magnetometer calibration matrix

0x14 (20d)

CREG_MAG_CAL2_3

Row 2, Column 3 of magnetometer calibration matrix

0x15 (21d)

CREG_MAG_CAL3_1

Row 3, Column 1 of magnetometer calibration matrix

0x16 (22d)

CREG_MAG_CAL3_2

Row 3, Column 2 of magnetometer calibration matrix

0x17 (23d)

CREG_MAG_CAL3_3

Row 3, Column 3 of magnetometer calibration matrix

0x18 (24d)

CREG_MAG_BIAS_X

Magnetometer X-axis bias

0x19 (25d)

CREG_MAG_BIAS_Y

Magnetometer Y-axis bias

0x1A (26d)

CREG_MAG_BIAS_Z

Magnetometer Z-axis bias

0x1B (27d)

CREG_ACCEL_CAL1_1

Row 1, Column 1 of accelerometer calibration matrix

0x1C (28d)

CREG_ACCEL_CAL1_2

Row 1, Column 2 of accelerometer calibration matrix

0x1D (29d)

CREG_ACCEL_CAL1_3

Row 1, Column 3 of accelerometer calibration matrix

0x1E (30d)

CREG_ACCEL_CAL2_1

Row 2, Column 1 of accelerometer calibration matrix

0x1F (31d)

CREG_ACCEL_CAL2_2

Row 2, Column 2 of accelerometer calibration matrix

0x20 (32d)

CREG_ACCEL_CAL2_3

Row 2, Column 3 of accelerometer calibration matrix

0x21 (33d)

CREG_ACCEL_CAL3_1

Row 3, Column 1 of accelerometer calibration matrix

0x22 (34d)

CREG_ACCEL_CAL3_2

Row 3, Column 2 of accelerometer calibration matrix

0x23 (35d)

CREG_ACCEL_CAL3_3

Row 3, Column 3 of accelerometer calibration matrix

0x24 (36d)

CREG_ACCEL_BIAS_X

Accelerometer X-axis bias

0x25 (37d)

CREG_ACCEL_BIAS_Y

Accelerometer Y-axis bias

0x26 (38d)

CREG_ACCEL_BIAS_Z

Accelerometer Z-axis bias

CREG_COM_SETTINGS

Address: 0 | 0x00 | 0b00000000

The CREG_COM_SETTINGS register is used to set the autopilot’s serial port baud rate and to enable or disable the automatic transmission of sensor data and estimated states (telemetry).

Table 18 CREG_COM_SETTINGS

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

BAUD_RATE

GPS_BAUD

Reserved

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

GPS

Reserved

SAT

Reserved

Table 19 CREG_COM_SETTINGS bits description

Bits

Name

Description

31:28

BAUD_RATE

Sets the baud rate of the UM7 main serial port:

Bit value

Baud rate

0

9600

1

14400

2

19200

3

38400

4

57600

5

115200

6

128000*

7

153600*

8

230400*

9

256000*

10

460800*

11

921600*

12:15

Reserved

  • Most PC serial ports do not support baud-rates above 115200

27:24

GPS_BAUD

Sets the baud rate of the UM7 auxiliary serial port:

Bit value

Baud rate

0

9600

1

14400

2

19200

3

38400

4

57600

5

115200

23:9

Reserved

These bits are reserved for future use

8

GPS

If set, this bit causes GPS data to be transmitted automatically whenever new GPS data is received. GPS data is stored in registers 125 to 130. These registers will be transmitted in a batch packet of length 6 starting at address 125.

7:5

Reserved

These bits are reserved for future use

4

SAT

If set, this bit causes satellite details to be transmitted whenever they are provided by the GPS. Satellite information is stored in registers 131 to 136. These registers will be transmitted in a batch packet of length 6 beginning at address 131.

3:0

Reserved

These bits are reserved for future use.

CREG_COM_RATES1

Address: 1 | 0x01 | 0b00000001

The CREG_COM_RATES1 register sets desired telemetry transmission rates in \(Hz\) for raw accelerometer, gyro, and magnetometer data. If the specified rate is \(0\), then no data is transmitted.

Table 20 CREG_COM_RATES1

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

RAW_ACCEL_RATE

RAW_GYRO_RATE

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

RAW_MAG_RATE

Reserved

Table 21 CREG_COM_RATES1 bits description

Bits

Name

Description

31:24

RAW_ACCEL_RATE

Specifies the desired raw accelerometer data broadcast rate in Hz. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

23:16

RAW_GYRO_RATE

Specifies the desired raw gyro data broadcast rate in Hz. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

15:8

RAW_MAG_RATE

Specifies the desired raw magnetometer data broadcast rate in Hz. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

7:0

Reserved

These bits are reserved for future use.

Raw accelerometer data is stored in registers 89 to 91. When the raw accel rate is greater than 0, the accelerometer data is transmitted in a batch packet of length 3 with start address 89.

Raw rate gyro data is stored in registers 86 to 88. When the raw gyro rate is greater than 0, the rate gyro data is transmitted in a batch packet of length 3 with start address 86.

Raw magnetometer data is stored in registers 92 to 94. When the raw magnetometer rate is greater than 0, the magnetometer data is transmitted in a batch packet of length 3 with start address 92.

If the ALL_RAW_RATE (“all raw data rate”) bitfield in CREG_COM_RATES2 is greater than 0, then all gyro, accelerometer, magnetometer, data will be transmitted together. The rates in the CREG_COM_RATES1 registers are then ignored and not used.

CREG_COM_RATES2

Address: 2 | 0x02 | 0b00000010

The CREG_COM_RATES2 register sets desired telemetry transmission rates for all raw data and temperature. If the specified rate is 0, then no data is transmitted.

Table 22 CREG_COM_RATES2

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

TEMP_RATE

Reserved

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

Reserved

ALL_RAW_RATE

Table 23 CREG_COM_RATES2 bits description

Bits

Name

Description

31:24

TEMP_RATE

Specifies the desired broadcast rate for temperature data. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

23:16

Reserved

These bits are reserved for future use.

15:8

Reserved

These bits are reserved for future use.

7:0

ALL_RAW_RATE

Specifies the desired broadcast rate for all raw sensor data. If set, this overrides the broadcast rate setting for individual raw data broadcast rates. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

Temperature data is stored in registers 95 and 96. If the temperature broadcast rate is greater than 0, then temperature data will be sent in a batch packet of length 2 with start address 95. If all raw data is being transmitted (as specified by byte 3 of this register), then the temperature data will be transmitted as part of the raw batch packet at “all raw rate” instead of the raw temperature rate.

Raw sensor/temperature data occupies registers 86 through 96. If the raw data broadcast rate is greater than 0, then all raw data and temperature data is sent in one batch packet of length 11, with start address 86.

CREG_COM_RATES3

Address: 3 | 0x03 | 0b00000011

The CREG_COM_RATES3 register sets desired telemetry transmission rates for processed sensor data. If the specified rate is 0, then no data is transmitted.

Table 24 CREG_COM_RATES3

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

PROC_ACCEL_RATE

PROC_GYRO_RATE

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

PROC_MAG_RATE

Reserved

Table 25 CREG_COM_RATES3 bits description

Bits

Name

Description

31:24

PROC_ACCEL_RATE

Specifies the desired broadcast rate for processed accelerometer data. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

23:16

PROC_GYRO_RATE

Specifies the desired broadcast rate for processed rate gyro data. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

15:8

PROC_MAG_RATE

Specifies the desired broadcast rate for processed magnetometer data. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

7:0

Reserved

These bits are reserved for future use.

Processed accelerometer data is stored in registers 101 to 104. If the specified broadcast rate is greater than 0, then the data will be transmitted in a batch packet of length 4 and start address 104.

Processed rate gyro data is stored in registers 97 to 100. If the specified broadcast rate is greater than 0, then the data will be transmitted in a batch packet of length 4 and start address 100.

Processed magnetometer data is stored in registers 105 to 108. If the specified broadcast rate is greater than 0, then the data will be transmitted in a batch packet of length 4 and start address 108.

If the ALL_PROC_RATE “all processed data broadcast rate” setting in the register CREG_COM_RATES4 is not zero, then the rates specified in the CREG_COM_RATES3 register are overridden.

CREG_COM_RATES4

Address: 4 | 0x04 | 0b00000100

The CREG_COM_RATES4 register defines the desired telemetry transmission rates for all processed data. If the specified rate is 0, then no data is transmitted.

Table 26 CREG_COM_RATES4

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

Reserved

Reserved

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

Reserved

ALL_PROC_RATE

Table 27 CREG_COM_RATES4 bits description

Bits

Name

Description

31:24

Reserved

These bits are reserved for future use.

23:16

Reserved

These bits are reserved for future use.

15:8

Reserved

These bits are reserved for future use.

7:0

ALL_PROC_RATE

Specifies the desired broadcast rate for raw all processed data. If set, this overrides the broadcast rate setting for individual processed data broadcast rates. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

All processed data comprises registers 97 through 108 (a total of 12 registers). If ALL_PROC_RATE is non-zero, the processed data will be transmitted as a single packet of batch length 12, starting at address 97.

CREG_COM_RATES5

Address: 5 | 0x05 | 0b00000101

The CREG_COM_RATES5 register sets desired telemetry transmission rates for quaternions, Euler Angles, position, and velocity estimates. If the specified rate is 0, then no data is transmitted.

Table 28 CREG_COM_RATES5

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

QUAT_RATE

EULER_RATE

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

POSITION_RATE

VELOCITY_RATE

Table 29 CREG_COM_RATES5 bits description

Bits

Name

Description

31:24

QUAT_RATE

Specifies the desired broadcast rate for quaternion data. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

23:16

EULER_RATE

Specifies the desired broadcast rate for Euler Angle data. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

15:8

POSITION_RATE

Specifies the desired broadcast rate position. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

7:0

VELOCITY_RATE

Specifies the desired broadcast rate for velocity. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

Quaternion data is stored in registers 109 to 111. If the specified broadcast rate is greater than 0, then the data will be transmitted in a batch packet with length 3 and start address 109.

Euler Angle data is stored in registers 112 to 116. If the specified broadcast rate is greater than 0, then the data will be transmitted in a batch packet of length 5 and start address 112.

Position data is stored in registers 117 to 120. If the specified broadcast rate is greater than 0, then the data will be transmitted in a batch packet of length 4 and start address 117.

Velocity data is stored in registers 121 to 124. If the specified broadcast rate is greater than 0, then the data will be transmitted in a batch packet of length 4 and start address 121.

If the “pose broadcast rate” setting in register CREG_COM_RATES6 is not zero, then the rates specified by EULER_RATE and POSITION_RATE are overridden.

CREG_COM_RATES6

Address: 6 | 0x06 | 0b00000110

The CREG_COM_RATES6 register sets desired telemetry transmission rates for pose (Euler/position packet), health, and gyro bias estimates. If the specified rate is 0, then no data is transmitted.

Table 30 CREG_COM_RATES6

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

POSE_RATE

Reserved

HEALTH_RATE

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

GYRO_BIAS_RATE

Reserved

Table 31 CREG_COM_RATES6 bits description

Bits

Name

Description

31:24

POSE_RATE

Specifies the desired broadcast rate for pose (Euler Angle and position) data. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

23:20

Reserved

These bits are reserved for future use.

19:16

HEALTH_RATE

Specifies the desired broadcast rate for the sensor health packet.

Bit value

Frequency, Hz

0

Off

1

0.125

2

0.25

3

0.5

4

1

5

2

6

4

7:15

Unused *

  • Will default to 1Hz

15:8

GYRO_BIAS_RATE

Specifies the desired broadcast rate for gyro bias estimates. The data is stored as an unsigned 8-bit integer, yielding a maximum rate of 255 Hz.

7:0

Reserved

These bits are reserved for future use.

Pose data (Euler Angles and position) is stored in registers 112 to 120. If the pose rate is greater than 0, then pose data will be transmitted in a batch packet with length 9 and start address 112.

Health data is stored in register address 85. If the health rate is not 0, then health data will be transmitted as a non-batch packet with address 85.

CREG_COM_RATES7

Address: 7 | 0x07 | 0b00000111

Table 32 CREG_COM_RATES7

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

HEALTH_RATE

POSE_RATE

ATTITUDE_RATE

SENSOR_RATE

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

RATES_RATE

GPS_POSE_RATE

QUAT_RATE

Reserved

Table 33 CREG_COM_RATES7 bits description

Bits

Name

Description

31:28

HEALTH_RATE

Specifies the desired broadcast rate for Redshift Labs NMEA-style health packet.

Bit value

Frequency, Hz

0

Off

1

1

2

2

3

4

4

5

5

10

6

15

7

20

8

30

9

40

10

50

11

60

12

70

13

80

14

90

15

100

27:24

POSE_RATE

Specifies the desired broadcast rate for Redshift Labs NMEA-style pose (Euler Angle/position) packet.

Bit value

Frequency, Hz

0

Off

1

1

2

2

3

4

4

5

5

10

6

15

7

20

8

30

9

40

10

50

11

60

12

70

13

80

14

90

15

100

23:20

ATTITUDE_RATE

Specifies the desired broadcast rate for Redshift Labs NMEA-style attitude packet.

Bit value

Frequency, Hz

0

Off

1

1

2

2

3

4

4

5

5

10

6

15

7

20

8

30

9

40

10

50

11

60

12

70

13

80

14

90

15

100

19:16

SENSOR_RATE

Specifies the desired broadcast rate for Redshift Labs NMEA-style sensor data packet.

Bit value

Frequency, Hz

0

Off

1

1

2

2

3

4

4

5

5

10

6

15

7

20

8

30

9

40

10

50

11

60

12

70

13

80

14

90

15

100

15:12

RATES_RATE

Specifies the desired broadcast rate for Redshift Labs NMEA-style rate data packet.

Bit value

Frequency, Hz

0

Off

1

1

2

2

3

4

4

5

5

10

6

15

7

20

8

30

9

40

10

50

11

60

12

70

13

80

14

90

15

100

11:8

GPS_POSE_RATE

Specifies the desired broadcast rate for Redshift Labs NMEA-style GPS pose packet.

Bit value

Frequency, Hz

0

Off

1

1

2

2

3

4

4

5

5

10

6

15

7

20

8

30

9

40

10

50

11

60

12

70

13

80

14

90

15

100

7:4

QUAT_RATE

Specifies the desired broadcast rate for Redshift Labs NMEA-style quaternion packet.

Bit value

Frequency, Hz

0

Off

1

1

2

2

3

4

4

5

5

10

6

15

7

20

8

30

9

40

10

50

11

60

12

70

13

80

14

90

15

100

3:0

Reserved

These bits are reserved for future use.

CREG_MISC_SETTINGS

Address: 8 | 0x08 | 0b00001000

This register contains miscellaneous filter and sensor control options.

Table 34 CREG_MISC_SETTINGS

Byte 3

Byte 2

31

30

29

28

27

26

25

24

23

22

21

20

19

18

17

16

Reserved

Byte 1

Byte 0

15

14

13

12

11

10

9

8

7

6

5

4

3

2

1

0

Reserved

PPS

Reserved

ZG

Q

MAG

Table 35 CREG_MISC_SETTINGS bits description

Bits

Name

Description

31:9

Reserved

These bits are reserved for future use.

8

PPS

If set, this bit causes the TX2 pin on the IO Expansion header to be used as the PPS input from an external GPS module. PPS pulses will then be used to synchronize the system clock to UTC time of day.

7:3

Reserved

These bits are reserved for future use.

2

ZG

If set, this bit causes the devicee to attempt to measure the rate gyro bias on startup. The sensor must be stationary on startup for this feature to work properly.

1

Q

If this bit is set, the sensor will run in quaternion mode instead of Euler Angle mode.

0

MAG

If set, the magnetometer will be used in state updates.

CREG_HOME_NORTH

Address: 9 | 0x09 | 0b00001001

This register sets the north home latitude in degrees, used to convert GPS coordinates to position in meters from home.

Table 36 CREG_HOME_NORTH

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_HOME_EAST

Address: 10 | 0x0A | 0b00001010

This register sets the east home longitude in degrees, used to convert GPS coordinates to position in meters from home.

Table 37 CREG_HOME_EAST

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_HOME_UP

Address: 11 | 0x0B | 0b00001011

This register sets the home altitude in meters. Used to convert GPS coordinates to position in meters from home.

Table 38 CREG_HOME_UP

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_GYRO_TRIM_X

Address: 12 | 0x0C | 0b00001100

This register sets the x-axis rate gyro trim, which is used to add additional bias compensation for the rate gyros during calls to the ZERO_GYRO_BIAS command.

Table 39 CREG_GYRO_TRIM_X

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_GYRO_TRIM_Y

Address: 13 | 0x0D | 0b00001101

This register sets the y-axis rate gyro trim, which is used to add additional bias compensation for the rate gyros during calls to the ZERO_GYRO_BIAS command.

Table 40 CREG_GYRO_TRIM_Y

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_GYRO_TRIM_Z

Address: 14 | 0x0E | 0b00001110

This register sets the z-axis rate gyro trim, which is used to add additional bias compensation for the rate gyros during calls to the ZERO_GYRO_BIAS command.

Table 41 CREG_GYRO_TRIM_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_MAG_CAL1_1 to CREG_MAG_CAL3_3

Address: 15 to 23 | 0x0F to 0x17 | 0b00001111 to 0b00010111

These registers store the 9 entries into a 3x3 matrix that is used to perform soft-iron calibration of the magnetometer on the device. These terms can be computed by performing magnetometer calibration with the Redshift labs Serial Interface.

\[\begin{split}\begin{bmatrix} \texttt{CREG_MAG_CAL1_1} & \texttt{CREG_MAG_CAL1_2} & \texttt{CREG_MAG_CAL1_3} \\ \texttt{CREG_MAG_CAL2_1} & \texttt{CREG_MAG_CAL2_2} & \texttt{CREG_MAG_CAL2_3} \\ \texttt{CREG_MAG_CAL3_1} & \texttt{CREG_MAG_CAL3_2} & \texttt{CREG_MAG_CAL3_3} \\ \end{bmatrix}\end{split}\]
Table 42 CREG_MAG_CAL1_1 to CREG_MAG_CAL3_3

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

CREG_MAG_CAL1_1: 32-bit IEEE Floating Point Value

CREG_MAG_CAL1_2: 32-bit IEEE Floating Point Value

CREG_MAG_CAL1_3: 32-bit IEEE Floating Point Value

CREG_MAG_CAL2_1: 32-bit IEEE Floating Point Value

CREG_MAG_CAL2_2: 32-bit IEEE Floating Point Value

CREG_MAG_CAL2_3: 32-bit IEEE Floating Point Value

CREG_MAG_CAL3_1: 32-bit IEEE Floating Point Value

CREG_MAG_CAL3_2: 32-bit IEEE Floating Point Value

CREG_MAG_CAL3_3: 32-bit IEEE Floating Point Value

CREG_MAG_BIAS_X

Address: 24 | 0x18 | 0b00011000

This register stores a bias term for the magnetometer x-axis for hard-iron calibration. This term can be computed by performing magnetometer calibration with the Redshift labs Serial Interface.

Table 43 CREG_MAG_BIAS_X

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_MAG_BIAS_Y

Address: 25 | 0x19 | 0b00011001

This register stores a bias term for the magnetometer y-axis for hard-iron calibration. This term can be computed by performing magnetometer calibration with the Redshift labs Serial Interface.

Table 44 CREG_MAG_BIAS_Y

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_MAG_BIAS_Z

Address: 26 | 0x1A | 0b00011010

This register stores a bias term for the magnetometer z-axis for hard-iron calibration. This term can be computed by performing magnetometer calibration with the Redshift labs Serial Interface.

Table 45 CREG_MAG_BIAS_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_ACCEL_CAL1_1 to CREG_ACCEL_CAL3_3

Addresses: 27 to 35 | 0x1B to 0x23 | 0b00011011 to 0b00100011

These registers store the 9 entries into a 3x3 matrix that are used to compensate for cross axis misalignment.

\[\begin{split}\begin{bmatrix} \texttt{CREG_ACCEL_CAL1_1} & \texttt{CREG_ACCEL_CAL1_2} & \texttt{CREG_ACCEL_CAL1_3} \\ \texttt{CREG_ACCEL_CAL2_1} & \texttt{CREG_ACCEL_CAL2_2} & \texttt{CREG_ACCEL_CAL2_3} \\ \texttt{CREG_ACCEL_CAL3_1} & \texttt{CREG_ACCEL_CAL3_2} & \texttt{CREG_ACCEL_CAL3_3} \\ \end{bmatrix}\end{split}\]
Table 46 CREG_ACCEL_CAL1_1 to CREG_ACCEL_CAL3_3

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_ACCEL_BIAS_X

Address: 36 | 0x24 | 0b00100100

This register stores a bias term for the accelerometer x-axis for bias calibration. This term can be computed by performing calibrate accelerometers command within the Redshift labs Serial Interface.

Table 47 CREG_ACCEL_BIAS_X

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_ACCEL_BIAS_Y

Address: 37 | 0x25 | 0b00100101

This register stores a bias term for the accelerometer y-axis for bias calibration. This term can be computed by performing calibrate accelerometers command within the Redshift labs Serial Interface.

Table 48 CREG_ACCEL_BIAS_Y

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

CREG_ACCEL_BIAS_Z

Address: 38 | 0x26 | 0b00100110

This register stores a bias term for the accelerometer z-axis for bias calibration. This term can be computed by performing calibrate accelerometers command within the Redshift labs Serial Interface.

Table 49 CREG_ACCEL_BIAS_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

Data Registers

Table 50 Data Registers

Address

Register Name

Register Description

0x55 (85d)

DREG_HEALTH

Information about the health and status of the UM7

0x56 (86d)

DREG_GYRO_RAW_XY

Raw X and Y rate gyro data

0x57 (87d)

DREG_GYRO_RAW_Z

Raw Z rate gyro data

0x58 (88d)

DREG_GYRO_RAW_TIME

Time at which rate gyro data was acquired

0x59 (89d)

DREG_ACCEL_RAW_XY

Raw X and Y accelerometer data

0x5A (90d)

DREG_ACCEL_RAW_Z

Raw Z accelerometer data

0x5B (91d)

DREG_ACCEL_RAW_TIME

Time at which raw accelerometer data was acquired

0x5C (92d)

DREG_MAG_RAW_XY

Raw X and Y magnetometer data

0x5D (93d)

DREG_MAG_RAW_Z

Raw Z magnetometer data

0x5E (94d)

DREG_MAG_RAW_TIME

Time at which magnetometer data was acquired

0x5F (95d)

DREG_TEMPERATURE

Temperature data

0x60 (96d)

DREG_TEMPERATURE_TIME

Time at which temperature data was acquired

0x61 (97d)

DREG_GYRO_PROC_X

Processed x-axis rate gyro data

0x62 (98d)

DREG_GYRO_PROC_Y

Processed y-axis rate gyro data

0x63 (99d)

DREG_GYRO_PROC_Z

Processed z-axis rate gyro data

0x64 (100d)

DREG_GYRO_PROC_TIME

Time at which rate gyro data was acquired

0x65 (101d)

DREG_ACCEL_PROC_X

Processed x-axis accel data

0x66 (102d)

DREG_ACCEL_PROC_Y

Processed y-axis accel data

0x67 (103d)

DREG_ACCEL_PROC_Z

Processed z-axis accel data

0x68 (104d)

DREG_ACCEL_PROC_TIME

Time at which accelerometer data was acquired

0x69 (105d)

DREG_MAG_PROC_X

Processed x-axis magnetometer data

0x6A (106d)

DREG_MAG_PROC_Y

Processed y-axis magnetometer data

0x6B (107d)

DREG_MAG_PROC_Z

Processed z-axis magnetometer data

0x6C (108d)

DREG_MAG_PROC_TIME

Time at which magnetometer data was acquired

0x6D (109d)

DREG_QUAT_AB

Quaternion elements A and B

0x6E (110d)

DREG_QUAT_CD

Quaternion elements C and D

0x6F (111d)

DREG_QUAT_TIME

Time when sensor was at the specified quaternion rotation

0x70 (112d)

DREG_EULER_PHI_THETA

Roll and pitch angles

0x71 (113d)

DREG_EULER_PSI

Yaw angle

0x72 (114d)

DREG_EULER_PHI_THETA_DOT

Roll and pitch angle rates

0x73 (115d)

DREG_EULER_PSI_DOT

Yaw rate

0x74 (116d)

DREG_EULER_TIME

Time of computed Euler attitude and rates

0x75 (117d)

DREG_POSITION_NORTH

North position in meters

0x76 (118d)

DREG_POSITION_EAST

East position in meters

0x77 (119d)

DREG_POSITION_UP

Altitude in meters

0x78 (120d)

DREG_POSITION_TIME

Time of estimated position

0x79 (121d)

DREG_VELOCITY_NORTH

North velocity

0x7A (122d)

DREG_VELOCITY_EAST

East velocity

0x7B (123d)

DREG_VELOCITY_UP

Altitude velocity

0x7C (124d)

DREG_VELOCITY_TIME

Time of velocity estimate

0x7D (125d)

DREG_GPS_LATITUDE

GPS latitude

0x7E (126d)

DREG_GPS_LONGITUDE

GPS longitude

0x7F (127d)

DREG_GPS_ALTITUDE

GPS altitude

0x80 (128d)

DREG_GPS_COURSE

GPS course

0x81 (129d)

DREG_GPS_SPEED

GPS speed

0x82 (130d)

DREG_GPS_TIME

GPS time (UTC time of day in seconds)

0x83 (131d)

DREG_GPS_SAT_1_2

GPS satellite information

0x84 (132d)

DREG_GPS_SAT_3_4

GPS satellite information

0x85 (133d)

DREG_GPS_SAT_5_6

GPS satellite information

0x86 (134d)

DREG_GPS_SAT_7_8

GPS satellite information

0x87 (135d)

DREG_GPS_SAT_9_10

GPS satellite information

0x88 (136d)

DREG_GPS_SAT_11_12

GPS satellite information

0x89 (137d)

DREG_GYRO_BIAS_X

Gyro x-axis bias estimate

0x8A (138d)

DREG_GYRO_BIAS_Y

Gyro y-axis bias estimate

0x8B (139d)

DREG_GYRO_BIAS_Z

Gyro z-axis bias estimate

0x8C (140d)

RESERVED

Reserved

0x8D (141d)

RESERVED

Reserved

0x8E (142d)

RESERVED

Reserved

0x8F (143d)

RESERVED

Reserved

0x90 (144d)

RESERVED

Reserved

0x91 (145d)

RESERVED

Reserved

0x92 (146d)

RESERVED

Reserved

0x93 (147d)

RESERVED

Reserved

DREG_HEALTH

Address: 85 | 0x55 | 0b01010101

The health register reports the current status of the GPS module and the other sensors on the board. Monitoring the health register is the easiest way to monitor the quality of the GPS lock and to watch for other problems that could affect the behavior of the board.

Table 51 DREG_HEALTH

Byte 3

31

30

29

28

27

26

25

24

SATS_USED

HDOP

Byte 2

23

22

21

20

19

18

17

16

HDOP

Byte 1

15

14

13

12

11

10

9

8

SATS_IN_VIEW

Res.

OVF

Byte 0

7

6

5

4

3

2

1

0

Res.

MG_N

ACC_N

ACCEL

GYRO

MAG

GPS

Table 52 DREG_HEALTH bits description

Bits

Name

Description

31:26

SATS_USED

Reports the number of satellites used in the position solution.

25:16

HDOP

Reports the horizontal dilution of precision (HDOP) reported by the GPS. The actual HDOP value is equal to the contents of the HDOP bits divided by 10.

15:10

SATS_IN_VIEW

Reports the number of satellites in view.

9

Res.

This bit is reserved for future use.

8

OVF

Overflow bit. This bit is set if the UM7 is attempting to transmit data over the serial port faster than is allowed given the baud-rate. If this bit is set, reduce broadcast rates in the COM_RATES registers.

7:6

Res.

These bits are reserved for future use.

5

MG_N

This bit is set if the sensor detects that the norm of the magnetometer measurement is too far away from 1.0 to be trusted. Usually indicates bad calibration, local field distortions, or both.

4

ACC_N

This bit is set if the sensor detects that the norm of the accelerometer measurement is too far away from 1G to be used (i.e. during aggressive acceleration or high vibration).

3

ACCEL

This bit will be set if the accelerometer fails to initialize on startup.

2

GYRO

This bit will be set if the rate gyro fails to initialize on startup.

1

MAG

This bit will be set if the magnetometer fails to initialize on startup.

0

GPS

This bit is set if the GPS fails to send a packet for more than two seconds. If a GPS packet is ever received, this bit is cleared.

DREG_GYRO_RAW_XY

Address: 86 | 0x56 | 0b01010110

Contains raw X and Y axis rate gyro data.

Table 53 DREG_GYRO_RAW_XY

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro X (2’s complement 16-bit integer)

Gyro Y (2’s complement 16-bit integer)

DREG_GYRO_RAW_Z

Address: 87 | 0x57 | 0b01010111

Contains raw Z axis rate gyro data

Table 54 DREG_GYRO_RAW_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro Z (2’s complement 16-bit integer)

Reserved

DREG_GYRO_RAW_TIME

Address: 88 | 0x58 | 0b01011000

Contains time at which the last rate gyro data was acquired.

Table 55 DREG_GYRO_RAW_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

DREG_ACCEL_RAW_XY

Address: 89 | 0x59 | 0b01011001

Contains raw X and Y axis accelerometer data.

Table 56 DREG_ACCEL_RAW_XY

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Accel X (2’s complement 16-bit integer)

Accel Y (2’s complement 16-bit integer)

DREG_ACCEL_RAW_Z

Address: 90 | 0x5A | 0b01011010

Contains raw Z axis accelerometer data.

Table 57 DREG_ACCEL_RAW_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Accel Z (2’s complement 16-bit integer)

Reserved

DREG_ACCEL_RAW_TIME

Address: 91 | 0x5B | 0b01011011

Contains time at which the last accelerometer data was acquired.

Table 58 DREG_ACCEL_RAW_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

DREG_MAG_RAW_XY

Address: 92 | 0x5C | 0b01011100

Contains raw X and Y axis magnetometer data.

Table 59 DREG_MAG_RAW_XY

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Mag X (2’s complement 16-bit integer)

Mag Y (2’s complement 16-bit integer)

DREG_MAG_RAW_Z

Address: 93 | 0x5D | 0b01011101

Contains raw Z axis magnetometer data.

Table 60 DREG_MAG_RAW_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Mag Z (2’s complement 16-bit integer)

Reserved

DREG_MAG_RAW_TIME

Address: 94 | 0x5E | 0b01011110

Contains time at which the last magnetometer data was acquired.

Table 61 DREG_MAG_RAW_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

DREG_TEMPERATURE

Address: 95 | 0x5F | 0b01011111

Contains the temperature output of the onboard temperature sensor.

Table 62 DREG_TEMPERATURE

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Temperature in degrees Celcius (32-bit IEEE Floating Point)

DREG_TEMPERATURE_TIME

Address: 96 | 0x60 | 0b01100000

Contains time at which the last temperature was acquired.

Table 63 DREG_TEMPERATURE_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

32-bit IEEE Floating Point Value

DREG_GYRO_PROC_X

Address: 97 | 0x61 | 0b01100001

Contains the actual measured angular rate for the \(x\) axis in degrees/sec after calibration has been applied.

Table 64 DREG_GYRO_PROC_X

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro X in degrees / sec (32-bit IEEE Floating Point Value)

DREG_GYRO_PROC_Y

Address: 98 | 0x62 | 0b01100010

Contains the actual measured angular rate for the \(y\) axis in degrees/sec after calibration has been applied.

Table 65 DREG_GYRO_PROC_Y

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro Y in degrees / sec (32-bit IEEE Floating Point Value)

DREG_GYRO_PROC_Z

Address: 99 | 0x63 | 0b01100011

Contains the actual measured angular rate for the \(z\) axis in degrees/sec after calibration has been applied.

Table 66 DREG_GYRO_PROC_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro Z in degrees / sec (32-bit IEEE Floating Point Value)

DREG_GYRO_PROC_TIME

Address: 100 | 0x64 | 0b01100100

Contains the time at which the last rate gyro data was measured.

Table 67 DREG_GYRO_PROC_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro time (32-bit IEEE Floating Point Value)

DREG_ACCEL_PROC_X

Address: 101 | 0x65 | 0b01100101

Contains the actual measured acceleration in \(m/s^2\) for the \(x\) axis after calibration has been applied.

Table 68 DREG_ACCEL_PROC_X

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Accel X in \(m/s^2\) (32-bit IEEE Floating Point Value)

DREG_ACCEL_PROC_Y

Address: 102 | 0x66 | 0b01100110

Contains the actual measured acceleration in \(m/s^2\) for the \(y\) axis after calibration has been applied.

Table 69 DREG_ACCEL_PROC_Y

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Accel Y in \(m/s^2\) (32-bit IEEE Floating Point Value)

DREG_ACCEL_PROC_Z

Address: 103 | 0x67 | 0b01100111

Contains the actual measured acceleration in \(m/s^2\) for the \(z\) axis after calibration has been applied.

Table 70 DREG_ACCEL_PROC_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Accel Z in \(m/s^2\) (32-bit IEEE Floating Point Value)

DREG_ACCEL_PROC_TIME

Address: 104 | 0x68 | 0b01101000

Contains the time at which the acceleration was measured.

Table 71 DREG_ACCEL_PROC_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Accel time (32-bit IEEE Floating Point Value)

DREG_MAG_PROC_X

Address: 105 | 0x69 | 0b01101001

Contains the actual measured magnetic field for the \(x\) axis after calibration has been applied.

Table 72 DREG_MAG_PROC_X

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Mag X (32-bit IEEE Floating Point Value)

DREG_MAG_PROC_Y

Address: 106 | 0x6A | 0b01101010

Contains the actual measured magnetic field for the \(y\) axis after calibration has been applied.

Table 73 DREG_MAG_PROC_Y

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Mag Y (32-bit IEEE Floating Point Value)

DREG_MAG_PROC_Z

Address: 107 | 0x6B | 0b01101011

Contains the actual measured magnetic field for the \(z\) axis after calibration has been applied.

Table 74 DREG_MAG_PROC_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Mag Z (32-bit IEEE Floating Point Value)

DREG_MAG_PROC_TIME

Address: 108 | 0x6C | 0b01101100

Contains the time at which magnetometer data was acquired.

Table 75 DREG_MAG_PROC_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Mag time (32-bit IEEE Floating Point Value)

DREG_QUAT_AB

Address: 109 | 0x6D | 0b01101101

Contains the first two components (\(a\) and \(b\)) of the estimated quaternion attitude.

\[\mathbf{q} = a+b\ \mathbf {i} +c\ \mathbf {j} +d\ \mathbf{k}\]
Table 76 DREG_QUAT_AB

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Quaternion A

Quaternion B

Table 77 DREG_QUAT_AB bits

Bits

Name

Description

31:16

Quaternion A

First quaternion component. Stored as a 16-bit signed integer. To get the actual value, divide by 29789.09091.

15:0

Quaternion B

Second quaternion component. Stored as a 16-bit signed integer. To get the actual value, divide by 29789.09091.

DREG_QUAT_CD

Address: 110 | 0x6E | 0b01101110

Contains the second two components (\(c\) and \(d\)) of the estimated quaternion attitude.

\[\mathbf{q} = a+b\ \mathbf {i} +c\ \mathbf {j} +d\ \mathbf{k}\]
Table 78 DREG_QUAT_CD

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Quaternion C

Quaternion D

Table 79 DREG_QUAT_CD bits

Bits

Name

Description

31:16

Quaternion C

Third quaternion component. Stored as a 16-bit signed integer. To get the actual value, divide by 29789.09091.

15:0

Quaternion D

Fourth quaternion component. Stored as a 16-bit signed integer. To get the actual value, divide by 29789.09091.

DREG_QUAT_TIME

Address: 111 | 0x6F | 0b01101111

Contains the time that the quaternion attitude was estimated.

Table 80 DREG_QUAT_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Quaternion time (32-bit IEEE Floating Point Value)

DREG_EULER_PHI_THETA

Address: 112 | 0x70 | 0b01110000

Contains the pitch and roll angle estimates.

Table 81 DREG_EULER_PHI_THETA

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Phi (roll)

Theta (Pitch)

Table 82 DREG_EULER_PHI_THETA bits

Bits

Name

Description

31:16

Phi (roll)

Roll angle. Stored as a 16-bit signed integer. To get the actual value, divide by 91.02222.

15:0

Theta (pitch)

Pitch angle. Stored as a 16-bit signed integer. To get the actual value, divide by 91.02222.

DREG_EULER_PSI

Address: 113 | 0x71 | 0b01110001

Contains the yaw angle estimate.

Table 83 DREG_EULER_PSI

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Psi (yaw)

Reserved

Table 84 DREG_EULER_PSI bits

Bits

Name

Description

31:16

Psi (yaw)

Yaw angle. Stored as a 16-bit signed integer. To get the actual value, divide by 91.02222.

15:0

Reserved

These bits are reserved for future use.

DREG_EULER_PHI_THETA_DOT

Address: 114 | 0x72 | 0b01110010

Contains the pitch and roll rate estimates.

Table 85 DREG_EULER_PHI_THETA_DOT

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Roll rate

Pitch rate

Table 86 DREG_EULER_PHI_THETA_DOT bits

Bits

Name

Description

31:16

Roll rate

Roll rate. Stored as a 16-bit signed integer. To get the actual value, divide by 16.0.

15:0

Pitch rate

Pitch rate. Stored as a 16-bit signed integer. To get the actual value, divide by 16.0.

DREG_EULER_PSI_DOT

Address: 115 | 0x73 | 0b01110011

Contains the yaw rate estimate.

Table 87 DREG_EULER_PSI_DOT

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Yaw rate

Reserved

Table 88 DREG_EULER_PHI_THETA_DOT bits

Bits

Name

Description

31:16

Yaw rate

Yaw rate. Stored as a 16-bit signed integer. To get the actual value, divide by 16.0.

15:0

Reserved

These bits are reserved for future use.

DREG_EULER_TIME

Address: 116 | 0x74 | 0b01110100

Contains the time that the Euler Angles were estimated.

Table 89 DREG_EULER_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Euler time (32-bit IEEE Floating Point Value)

DREG_POSITION_NORTH

Address: 117 | 0x75 | 0b01110101

Contains the measured north position in meters from the latitude specified in CREG_HOME_NORTH.

Table 90 DREG_POSITION_NORTH

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

North Position (32-bit IEEE Floating Point Value)

DREG_POSITION_EAST

Address: 118 | 0x76 | 0b01110110

Contains the measured east position in meters from the longitude specified in CREG_HOME_EAST.

Table 91 DREG_POSITION_EAST

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

East Position (32-bit IEEE Floating Point Value)

DREG_POSITION_UP

Address: 119 | 0x77 | 0b01110111

Contains the measured altitude in meters from the altitude specified in CREG_HOME_UP.

Table 92 DREG_POSITION_UP

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Altitude (32-bit IEEE Floating Point Value)

DREG_POSITION_TIME

Address: 120 | 0x78 | 0b01111000

Contains the time at which the position was acquired.

Table 93 DREG_POSITION_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Position Time (32-bit IEEE Floating Point Value)

DREG_VELOCITY_NORTH

Address: 121 | 0x79 | 0b01111001

Contains the measured north velocity in \(m/s\).

Table 94 DREG_VELOCITY_NORTH

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

North Velocity (32-bit IEEE Floating Point Value)

DREG_VELOCITY_EAST

Address: 122 | 0x7A | 0b01111010

Contains the measured east velocity in \(m/s\).

Table 95 DREG_VELOCITY_EAST

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

East Velocity (32-bit IEEE Floating Point Value)

DREG_VELOCITY_UP

Address: 123 | 0x7B | 0b01111011

Contains the measured altitude velocity in \(m/s\).

Table 96 DREG_VELOCITY_UP

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Altitude Velocity (32-bit IEEE Floating Point Value)

DREG_VELOCITY_TIME

Address: 124 | 0x7C | 0b01111100

Contains the time at which the velocity was measured.

Table 97 DREG_VELOCITY_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Velocity time (32-bit IEEE Floating Point Value)

DREG_GPS_LATITUDE

Address: 125 | 0x7D | 0b01111101

Contains the GPS-reported latitude in degrees.

Table 98 DREG_GPS_LATITUDE

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

GPS Latitude (32-bit IEEE Floating Point Value)

DREG_GPS_LONGITUDE

Address: 126 | 0x7E | 0b01111110

Contains the GPS-reported longitude in degrees.

Table 99 DREG_GPS_LONGITUDE

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

GPS Longitude (32-bit IEEE Floating Point Value)

DREG_GPS_ALTITUDE

Address: 127 | 0x7F | 0b01111111

Contains the GPS-reported altitude in meters.

Table 100 DREG_GPS_ALTITUDE

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

GPS Altitude (32-bit IEEE Floating Point Value)

DREG_GPS_COURSE

Address: 128 | 0x80 | 0b10000000

Contains the GPS-reported course in degrees.

Table 101 DREG_GPS_COURSE

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

GPS Course (32-bit IEEE Floating Point Value)

DREG_GPS_SPEED

Address: 129 | 0x81 | 0b10000001

Contains the GPS-reported speed in \(m/s\).

Table 102 DREG_GPS_SPEED

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

GPS Speed (32-bit IEEE Floating Point Value)

DREG_GPS_TIME

Address: 130 | 0x82 | 0b10000010

Contains the GPS-reported time in seconds from the last epoch.

Table 103 DREG_GPS_TIME

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

GPS Time (32-bit IEEE Floating Point Value)

DREG_GPS_SAT_1_2

Address: 131 | 0x83 | 0b10000011

Contains satellite ID and signal-to-noise ratio (SNR) for satellites 1 and 2.

Table 104 DREG_GPS_SAT_1_2

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Sat 1 ID

Sat 1 SNR

Sat 2 ID

Sat 2 SNR

Table 105 DREG_GPS_SAT_1_2 bits

Bits

Name

Description

31:24

Sat 1 ID

Satellite ID

23:16

Sat 1 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

15:8

Sat 2 ID

Satellite ID

7:0

Sat 2 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

DREG_GPS_SAT_3_4

Address: 132 | 0x84 | 0b10000100

Contains satellite ID and signal-to-noise ratio (SNR) for satellites 3 and 4.

Table 106 DREG_GPS_SAT_3_4

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Sat 3 ID

Sat 3 SNR

Sat 4 ID

Sat 4 SNR

Table 107 DREG_GPS_SAT_3_4 bits

Bits

Name

Description

31:24

Sat 3 ID

Satellite ID

23:16

Sat 3 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

15:8

Sat 4 ID

Satellite ID

7:0

Sat 4 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

DREG_GPS_SAT_5_6

Address: 133 | 0x85 | 0b10000101

Contains satellite ID and signal-to-noise ratio (SNR) for satellites 5 and 6.

Table 108 DREG_GPS_SAT_5_6

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Sat 5 ID

Sat 5 SNR

Sat 6 ID

Sat 6 SNR

Table 109 DREG_GPS_SAT_5_6 bits

Bits

Name

Description

31:24

Sat 5 ID

Satellite ID

23:16

Sat 5 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

15:8

Sat 6 ID

Satellite ID

7:0

Sat 6 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

DREG_GPS_SAT_7_8

Address: 134 | 0x86 | 0b10000110

Contains satellite ID and signal-to-noise ratio (SNR) for satellites 7 and 8.

Table 110 DREG_GPS_SAT_7_8

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Sat 7 ID

Sat 7 SNR

Sat 8 ID

Sat 8 SNR

Table 111 DREG_GPS_SAT_7_8 bits

Bits

Name

Description

31:24

Sat 7 ID

Satellite ID

23:16

Sat 7 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

15:8

Sat 8 ID

Satellite ID

7:0

Sat 8 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

DREG_GPS_SAT_9_10

Address: 135 | 0x87 | 0b10000111

Contains satellite ID and signal-to-noise ratio (SNR) for satellites 9 and 10.

Table 112 DREG_GPS_SAT_9_10

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Sat 9 ID

Sat 9 SNR

Sat 10 ID

Sat 10 SNR

Table 113 DREG_GPS_SAT_9_10 bits

Bits

Name

Description

31:24

Sat 9 ID

Satellite ID

23:16

Sat 9 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

15:8

Sat 10 ID

Satellite ID

7:0

Sat 10 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

DREG_GPS_SAT_11_12

Address: 136 | 0x88 | 0b10001000

Contains satellite ID and signal-to-noise ratio (SNR) for satellites 11 and 12.

Table 114 DREG_GPS_SAT_11_12

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Sat 11 ID

Sat 11 SNR

Sat 12 ID

Sat 12 SNR

Table 115 DREG_GPS_SAT_11_12 bits

Bits

Name

Description

31:24

Sat 11 ID

Satellite ID

23:16

Sat 11 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

15:8

Sat 12 ID

Satellite ID

7:0

Sat 12 SNR

Signal-to-Noise Ratio of satellite as reported by GPS receiver.

DREG_GYRO_BIAS_X

Address: 137 | 0x89 | 0b10001001

Contains the estimated \(x\)-axis gyro bias in degrees/s.

Table 116 DREG_GYRO_BIAS_X

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro bias X (32-bit IEEE Floating Point Value)

DREG_GYRO_BIAS_Y

Address: 138 | 0x8A | 0b10001010

Contains the estimated \(y\)-axis gyro bias in degrees/s.

Table 117 DREG_GYRO_BIAS_Y

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro bias Y (32-bit IEEE Floating Point Value)

DREG_GYRO_BIAS_Z

Address: 139 | 0x8B | 0b10001011

Contains the estimated \(z\)-axis gyro bias in degrees/s.

Table 118 DREG_GYRO_BIAS_Z

Byte 3

Byte 2

Byte 1

Byte 0

31

30

24

23

22

16

15

14

8

7

6

0

Gyro bias Z (32-bit IEEE Floating Point Value)

Commands

Table 119 Commands

Address

Register Name

Register Description

0xAA (170d)

GET_FW_REVISION

Current firmware revision.

0xAB (171d)

FLASH_COMMIT

Write all current configuration settings to flash

0xAC (172d)

RESET_TO_FACTORY

Reset all settings to factory defaults

0xAD (173d)

ZERO_GYROS

Causes the rate gyro biases to be calibrated.

0xAE (174d)

SET_HOME_POSITION

Sets the current GPS location as position \((0,0)\)

0xAF (175d)

RESERVED

0xB0 (176d)

SET_MAG_REFERENCE

Sets the magnetometer reference vector

0xB1 (177d)

CALIBRATE_ACCELEROMETERS

Calibrates the accelerometer biases

0xB2 (178d)

RESERVED

0xB3 (179d)

RESET_EKF

Resets the EKF

0xB4 (180d)

RESERVED

0xB5 (181d)

RESERVED

0xB6 (182d)

RESERVED

0xB7 (183d)

RESERVED

0xB8 (184d)

RESERVED

0xB9 (185d)

RESERVED

0xBA (186d)

RESERVED

0xBB (187d)

RESERVED

0xBC (188d)

RESERVED

0xBD (189d)

RESERVED

0xBE (190d)

RESERVED

0xBF (191d)

RESERVED

0xC0 (192d)

RESERVED

0xC1 (193d)

RESERVED

0xC2 (194d)

RESERVED

0xC3 (195d)

RESERVED

0xC4 (196d)

RESERVED

0xC5 (197d)

RESERVED

0xC6 (198d)

RESERVED

0xC7 (199d)

RESERVED

GET_FW_REVISION

Address: 170 | 0xAA | 0b10101010

Causes the board to transmit a packet containing the firmware revision string. The firmware revision is a four-byte character sequence. The first firmware release version for the board, for example, was “UM7B”. The data section of the packet will contain four bytes.

FLASH_COMMIT

Address: 171 | 0xAB | 0b10101011

Causes the board to write all configuration settings to FLASH so that they will remain when the power is cycled.

RESET_TO_FACTORY

Address: 172 | 0xAC | 0b10101100

Causes the board to load default factory settings.

ZERO_GYROS

Address: 173 | 0xAD | 0b10101101

Causes the board to measure the gyro outputs and set the output trim registers to compensate for any non-zero bias. The board should be kept stationary while the zero operation is underway.

SET_HOME_POSITION

Address: 174 | 0xAE | 0b10101110

Sets the current GPS latitude, longitude, and altitude as the home position. All future positions will be referenced to the current GPS position.

SET_MAG_REFERENCE

Address: 176 | 0xB0 | 0b10110000

Sets the current yaw heading position as north.

CALIBRATE_ACCELEROMETERS

Address: 177 | 0xB1 | 0b10110001

Reboots the board and performs a crude calibration on the accelerometers. Best performed on a flat surface.

RESET_EKF

Address: 179 | 0xB3 | 0b10110011

Resets the EKF sensor fusion algorithm.

Reserved

This address is reserved for future use.