Register Overview¶
Table of Contents
There are three types of registers onboard the UM7:
configuration registers,
data registers, and
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¶
Address |
Register Name |
Register Description |
|
General communication settings |
|
|
Broadcast rate settings |
|
|
Broadcast rate settings |
|
|
Broadcast rate settings |
|
|
Broadcast rate settings |
|
|
Broadcast rate settings |
|
|
Broadcast rate settings |
|
|
Broadcast rate settings |
|
|
Misc. settings |
|
|
GPS north position to consider position 0 |
|
|
GPS east position to consider position 0 |
|
|
GPS altitude to consider position 0 |
|
|
Bias trim for x-axis rate gyro |
|
|
Bias trim for y-axis rate gyro |
|
|
Bias trim for z-axis rate gyro |
|
|
Row 1, Column 1 of magnetometer calibration matrix |
|
|
Row 1, Column 2 of magnetometer calibration matrix |
|
|
Row 1, Column 3 of magnetometer calibration matrix |
|
|
Row 2, Column 1 of magnetometer calibration matrix |
|
|
Row 2, Column 2 of magnetometer calibration matrix |
|
|
Row 2, Column 3 of magnetometer calibration matrix |
|
|
Row 3, Column 1 of magnetometer calibration matrix |
|
|
Row 3, Column 2 of magnetometer calibration matrix |
|
|
Row 3, Column 3 of magnetometer calibration matrix |
|
|
Magnetometer X-axis bias |
|
|
Magnetometer Y-axis bias |
|
|
Magnetometer Z-axis bias |
|
|
Row 1, Column 1 of accelerometer calibration matrix |
|
|
Row 1, Column 2 of accelerometer calibration matrix |
|
|
Row 1, Column 3 of accelerometer calibration matrix |
|
|
Row 2, Column 1 of accelerometer calibration matrix |
|
|
Row 2, Column 2 of accelerometer calibration matrix |
|
|
Row 2, Column 3 of accelerometer calibration matrix |
|
|
Row 3, Column 1 of accelerometer calibration matrix |
|
|
Row 3, Column 2 of accelerometer calibration matrix |
|
|
Row 3, Column 3 of accelerometer calibration matrix |
|
|
Accelerometer X-axis bias |
|
|
Accelerometer Y-axis bias |
|
|
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).
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 |
||||||||||||
Bits |
Name |
Description |
||||||||||||||||||||||||||||
|
BAUD_RATE |
Sets the baud rate of the UM7 main serial port:
|
||||||||||||||||||||||||||||
|
GPS_BAUD |
Sets the baud rate of the UM7 auxiliary serial port:
|
||||||||||||||||||||||||||||
|
Reserved |
These bits are reserved for future use |
||||||||||||||||||||||||||||
|
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. |
||||||||||||||||||||||||||||
|
Reserved |
These bits are reserved for future use |
||||||||||||||||||||||||||||
|
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. |
||||||||||||||||||||||||||||
|
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.
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 |
||||||||||||||
Bits |
Name |
Description |
|
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. |
|
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. |
|
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. |
|
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.
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 |
||||||||||||||
Bits |
Name |
Description |
|
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. |
|
Reserved |
These bits are reserved for future use. |
|
Reserved |
These bits are reserved for future use. |
|
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.
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 |
||||||||||||||
Bits |
Name |
Description |
|
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. |
|
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. |
|
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. |
|
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.
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 |
||||||||||||||
Bits |
Name |
Description |
|
Reserved |
These bits are reserved for future use. |
|
Reserved |
These bits are reserved for future use. |
|
Reserved |
These bits are reserved for future use. |
|
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.
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 |
||||||||||||||
Bits |
Name |
Description |
|
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. |
|
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. |
|
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. |
|
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.
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 |
||||||||||||||
Bits |
Name |
Description |
||||||||||||||||||
|
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. |
||||||||||||||||||
|
Reserved |
These bits are reserved for future use. |
||||||||||||||||||
|
HEALTH_RATE |
Specifies the desired broadcast rate for the sensor health packet.
|
||||||||||||||||||
|
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. |
||||||||||||||||||
|
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¶
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 |
||||||||||||
Bits |
Name |
Description |
||||||||||||||||||||||||||||||||||
|
HEALTH_RATE |
Specifies the desired broadcast rate for Redshift Labs NMEA-style health packet.
|
||||||||||||||||||||||||||||||||||
|
POSE_RATE |
Specifies the desired broadcast rate for Redshift Labs NMEA-style pose (Euler Angle/position) packet.
|
||||||||||||||||||||||||||||||||||
|
ATTITUDE_RATE |
Specifies the desired broadcast rate for Redshift Labs NMEA-style attitude packet.
|
||||||||||||||||||||||||||||||||||
|
SENSOR_RATE |
Specifies the desired broadcast rate for Redshift Labs NMEA-style sensor data packet.
|
||||||||||||||||||||||||||||||||||
|
RATES_RATE |
Specifies the desired broadcast rate for Redshift Labs NMEA-style rate data packet.
|
||||||||||||||||||||||||||||||||||
|
GPS_POSE_RATE |
Specifies the desired broadcast rate for Redshift Labs NMEA-style GPS pose packet.
|
||||||||||||||||||||||||||||||||||
|
QUAT_RATE |
Specifies the desired broadcast rate for Redshift Labs NMEA-style quaternion packet.
|
||||||||||||||||||||||||||||||||||
|
Reserved |
These bits are reserved for future use. |
CREG_MISC_SETTINGS¶
Address: 8 | 0x08 | 0b00001000¶
This register contains miscellaneous filter and sensor control options.
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 |
||||||||||
Bits |
Name |
Description |
|
Reserved |
These bits are reserved for future use. |
|
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. |
|
Reserved |
These bits are reserved for future use. |
|
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. |
|
Q |
If this bit is set, the sensor will run in quaternion mode instead of Euler Angle mode. |
|
MAG |
If set, the magnetometer will be used in state updates. |
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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¶
Address |
Register Name |
Register Description |
|
Information about the health and status of the UM7 |
|
|
Raw X and Y rate gyro data |
|
|
Raw Z rate gyro data |
|
|
Time at which rate gyro data was acquired |
|
|
Raw X and Y accelerometer data |
|
|
Raw Z accelerometer data |
|
|
Time at which raw accelerometer data was acquired |
|
|
Raw X and Y magnetometer data |
|
|
Raw Z magnetometer data |
|
|
Time at which magnetometer data was acquired |
|
|
Temperature data |
|
|
Time at which temperature data was acquired |
|
|
Processed x-axis rate gyro data |
|
|
Processed y-axis rate gyro data |
|
|
Processed z-axis rate gyro data |
|
|
Time at which rate gyro data was acquired |
|
|
Processed x-axis accel data |
|
|
Processed y-axis accel data |
|
|
Processed z-axis accel data |
|
|
Time at which accelerometer data was acquired |
|
|
Processed x-axis magnetometer data |
|
|
Processed y-axis magnetometer data |
|
|
Processed z-axis magnetometer data |
|
|
Time at which magnetometer data was acquired |
|
|
Quaternion elements A and B |
|
|
Quaternion elements C and D |
|
|
Time when sensor was at the specified quaternion rotation |
|
|
Roll and pitch angles |
|
|
Yaw angle |
|
|
Roll and pitch angle rates |
|
|
Yaw rate |
|
|
Time of computed Euler attitude and rates |
|
|
North position in meters |
|
|
East position in meters |
|
|
Altitude in meters |
|
|
Time of estimated position |
|
|
North velocity |
|
|
East velocity |
|
|
Altitude velocity |
|
|
Time of velocity estimate |
|
|
GPS latitude |
|
|
GPS longitude |
|
|
GPS altitude |
|
|
GPS course |
|
|
GPS speed |
|
|
GPS time (UTC time of day in seconds) |
|
|
GPS satellite information |
|
|
GPS satellite information |
|
|
GPS satellite information |
|
|
GPS satellite information |
|
|
GPS satellite information |
|
|
GPS satellite information |
|
|
Gyro x-axis bias estimate |
|
|
Gyro y-axis bias estimate |
|
|
Gyro z-axis bias estimate |
|
|
Reserved |
|
|
Reserved |
|
|
Reserved |
|
|
Reserved |
|
|
Reserved |
|
|
Reserved |
|
|
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.
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 |
|
Bits |
Name |
Description |
|
SATS_USED |
Reports the number of satellites used in the position solution. |
|
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. |
|
SATS_IN_VIEW |
Reports the number of satellites in view. |
|
Res. |
This bit is reserved for future use. |
|
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. |
|
Res. |
These bits are reserved for future use. |
|
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. |
|
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). |
|
ACCEL |
This bit will be set if the accelerometer fails to initialize on startup. |
|
GYRO |
This bit will be set if the rate gyro fails to initialize on startup. |
|
MAG |
This bit will be set if the magnetometer fails to initialize on startup. |
|
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_QUAT_AB¶
Address: 109 | 0x6D | 0b01101101¶
Contains the first two components (\(a\) and \(b\)) of the estimated quaternion attitude.
Byte 3 |
Byte 2 |
Byte 1 |
Byte 0 |
||||||||||||
31 |
30 |
… |
24 |
23 |
22 |
… |
16 |
15 |
14 |
… |
8 |
7 |
6 |
… |
0 |
Quaternion A |
Quaternion B |
||||||||||||||
Bits |
Name |
Description |
|
Quaternion A |
First quaternion component. Stored as a 16-bit signed integer. To get the actual value, divide by 29789.09091. |
|
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.
Byte 3 |
Byte 2 |
Byte 1 |
Byte 0 |
||||||||||||
31 |
30 |
… |
24 |
23 |
22 |
… |
16 |
15 |
14 |
… |
8 |
7 |
6 |
… |
0 |
Quaternion C |
Quaternion D |
||||||||||||||
Bits |
Name |
Description |
|
Quaternion C |
Third quaternion component. Stored as a 16-bit signed integer. To get the actual value, divide by 29789.09091. |
|
Quaternion D |
Fourth quaternion component. Stored as a 16-bit signed integer. To get the actual value, divide by 29789.09091. |
DREG_EULER_PHI_THETA¶
Address: 112 | 0x70 | 0b01110000¶
Contains the pitch and roll angle estimates.
Byte 3 |
Byte 2 |
Byte 1 |
Byte 0 |
||||||||||||
31 |
30 |
… |
24 |
23 |
22 |
… |
16 |
15 |
14 |
… |
8 |
7 |
6 |
… |
0 |
Phi (roll) |
Theta (Pitch) |
||||||||||||||
Bits |
Name |
Description |
|
Phi (roll) |
Roll angle. Stored as a 16-bit signed integer. To get the actual value, divide by 91.02222. |
|
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.
Byte 3 |
Byte 2 |
Byte 1 |
Byte 0 |
||||||||||||
31 |
30 |
… |
24 |
23 |
22 |
… |
16 |
15 |
14 |
… |
8 |
7 |
6 |
… |
0 |
Psi (yaw) |
Reserved |
||||||||||||||
Bits |
Name |
Description |
|
Psi (yaw) |
Yaw angle. Stored as a 16-bit signed integer. To get the actual value, divide by 91.02222. |
|
Reserved |
These bits are reserved for future use. |
DREG_EULER_PHI_THETA_DOT¶
Address: 114 | 0x72 | 0b01110010¶
Contains the pitch and roll rate estimates.
Byte 3 |
Byte 2 |
Byte 1 |
Byte 0 |
||||||||||||
31 |
30 |
… |
24 |
23 |
22 |
… |
16 |
15 |
14 |
… |
8 |
7 |
6 |
… |
0 |
Roll rate |
Pitch rate |
||||||||||||||
Bits |
Name |
Description |
|
Roll rate |
Roll rate. Stored as a 16-bit signed integer. To get the actual value, divide by 16.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.
Byte 3 |
Byte 2 |
Byte 1 |
Byte 0 |
||||||||||||
31 |
30 |
… |
24 |
23 |
22 |
… |
16 |
15 |
14 |
… |
8 |
7 |
6 |
… |
0 |
Yaw rate |
Reserved |
||||||||||||||
Bits |
Name |
Description |
|
Yaw rate |
Yaw rate. Stored as a 16-bit signed integer. To get the actual value, divide by 16.0. |
|
Reserved |
These bits are reserved for future use. |
DREG_GPS_SAT_1_2¶
Address: 131 | 0x83 | 0b10000011¶
Contains satellite ID and signal-to-noise ratio (SNR) for satellites 1 and 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 |
||||||||||||
Bits |
Name |
Description |
|
Sat 1 ID |
Satellite ID |
|
Sat 1 SNR |
Signal-to-Noise Ratio of satellite as reported by GPS receiver. |
|
Sat 2 ID |
Satellite ID |
|
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.
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 |
||||||||||||
Bits |
Name |
Description |
|
Sat 3 ID |
Satellite ID |
|
Sat 3 SNR |
Signal-to-Noise Ratio of satellite as reported by GPS receiver. |
|
Sat 4 ID |
Satellite ID |
|
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.
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 |
||||||||||||
Bits |
Name |
Description |
|
Sat 5 ID |
Satellite ID |
|
Sat 5 SNR |
Signal-to-Noise Ratio of satellite as reported by GPS receiver. |
|
Sat 6 ID |
Satellite ID |
|
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.
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 |
||||||||||||
Bits |
Name |
Description |
|
Sat 7 ID |
Satellite ID |
|
Sat 7 SNR |
Signal-to-Noise Ratio of satellite as reported by GPS receiver. |
|
Sat 8 ID |
Satellite ID |
|
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.
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 |
||||||||||||
Bits |
Name |
Description |
|
Sat 9 ID |
Satellite ID |
|
Sat 9 SNR |
Signal-to-Noise Ratio of satellite as reported by GPS receiver. |
|
Sat 10 ID |
Satellite ID |
|
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.
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 |
||||||||||||
Bits |
Name |
Description |
|
Sat 11 ID |
Satellite ID |
|
Sat 11 SNR |
Signal-to-Noise Ratio of satellite as reported by GPS receiver. |
|
Sat 12 ID |
Satellite ID |
|
Sat 12 SNR |
Signal-to-Noise Ratio of satellite as reported by GPS receiver. |
Commands¶
Address |
Register Name |
Register Description |
|
Current firmware revision. |
|
|
Write all current configuration settings to flash |
|
|
Reset all settings to factory defaults |
|
|
Causes the rate gyro biases to be calibrated. |
|
|
Sets the current GPS location as position \((0,0)\) |
|
|
||
|
Sets the magnetometer reference vector |
|
|
Calibrates the accelerometer biases |
|
|
||
|
Resets the EKF |
|
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
||
|
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.