In addition to the streaming Serial protocol, navX-sensors may be accessed over the I2C and SPI buses, using a register-based protocol. This page documents the register-based protocol used on both the I2C and SPI bus.
Register-based protocol overview
Unlike the streaming Serial protocol, which periodically sends out updates messages whenever new data is available, the register based protocol is a “polled” interface, in that the consumer of the navX-sensor data (in this case referred to as a “bus master”) can request data from the navX-sensor at any time. At the same time, when using the register-based protocol the bus master does not know when new data is available.
To help this situation, a timestamp – which is updated whenever new data is available – is made available. Therefore, the general approach to ensure each new data sample is retrieved is to regularly (at the current navX-sensor update rate) retrieve both the timestamp and the data of interest), and if the timestamp differs from the previous timestamp by the update rate as expressed in milliseconds, then the data sample just retrieved is current, and no data has been missed.
I2C Overview
The navX-sensor responds to 7-bit address 50 (0x32) on the I2C bus. If accessing the navX-sensor via the I2C bus, ensure that no other device at that address is on the same bus.
The navX-sensor I2C bus operates at a speed up to 400Khz.
When accessing the navX-sensor via the I2C bus, this following pattern is used:
– The I2C bus master sends the navX-sensor I2C address. The highest bit is set to indicate the bus master intends to write to the navX-sensor. If the highest bit is clear, this indicates the bus master intends to read from the navX-sensor.
– The I2C bus master next sends the starting register address it intends to write to or read from.
– The I2C bus master next initiates I2C bus transactions. The navX-sensor supports I2C burst mode for read operations, therefore the navX-sensor will respond with register values as long as the I2C bus master continues the transaction, and as long as the last register address has not yet been reached.
If instead the I2C bus master intends to write data to a writable navX-sensor register, the bus master should transmit the new register value immediately after sending the register address.
SPI Overview
The navX-sensor SPI data is communicated as follows:
– Most-significant bit first – Maximum Bitrate: 2mbps – Clock Polarity/Clock Phase – Mode 3
When accessing the navX-sensor via the SPI bus, this following pattern is used:
– When the SPI bus master is not communicating with the navX-sensor, the SPI bus master must hold the chip select (CS) line high.
– The SPI bus master lowers the CS line.
– The SPI bus master next transmits the register address it intends to read from or write to. If writing, the upper bit (0x80) must be set; if this upper bit is clear, this indicates a read transaction.
– If the SPI bus master is reading, it next transmits the count of registers it wishes to read from. This count must be at least 1, and must be not exceed the maximum register address less the requested register address.
– If the SPI bus master is writing, it transmits the register value to be written to the specified register address.
– The SPI bus master finally transmits an 8-bit CRC (see CRC calculation section below) which is calculated on the register address and count values previously transmitted.
– If the SPI bus master is writing, it raises the CS line to complete the write sequence.
– If the SPI bus master is reading:
– The SPI bus master raises the CS line.
– The SPI bus master delays for 200 microseconds, giving the navX-sensor sufficient time to prepare for the upcoming SPI bus transaction.
– The SPI bus master lowers the CS line.
– The SPI bus master initiates a series of SPI bus transactions, where the number of individual 8-bit transfers is equal to the count previously specified, plus one additional transfer for a CRC value transmitted by the nav-sensor.
– The SPI bus master raises the CS line to complete the read sequence.
CRC Calculation
The SPI protocol requires use of a cylic redundancy check (CRC) allowing the detection of corrupted data transmission over the high-speed SPI bus. Each SPI protocol message must end with a byte containing the CRC value.
The SPI protocol uses a 7-bit CRC with a polynomial value of 0x91.
For example code to calculate the CRC value, please see Line 445 of the IMURegisters.h source code.
navX-sensor Register Data Types
All multi-byte registers are in little-endian format.
All registers with ‘signed’ data are 2’s-complement.
Data Type | Range | Byte Count |
Unsigned Byte | 0 to 255 | 1 |
Unsigned Short | 0 to 65535 | 2 |
Signed Short | -32768 to 32768 | 2 |
signed hundredths | -327.68 to 327.67 | 2 |
Unsigned Hundredths | 0.0 to 655.35 | 2 |
Signed Thousandths | -32.768 to 32.767 | 2 |
Signed Pi Radians | -2 to 2 | 2 |
Q16.16 | -32768.9999 to 32767.9999 | 4 |
Unsigned Long | 0 to 4294967295 | 4 |
*Unsigned Hundredths: original value * 100 to rounded to nearest integer
*Signed Hundredths: original value * 100 rounded to nearest integer
*Signed Thousandths: original value * 1000 rounted to nearest integer
*Signed Pi Radians: original value * 16384 rounded to nearest integer
navX-sensor Register Map
Address (Hex) | Name | Access | Range/Data Type |
0x00 | WhoAmI | Read-only | 50 (0x32): navX-sensor |
0x01 | Board Revision | Read-only | Unsigned byte |
0x02 | Firmware Major Version | Read-only | Unsigned byte |
0x03 | Firmware Minor Version | Read-only | Unsigned byte |
0x04 | Update Rate | Read/write | Unsigned byte (Hz) |
0x05 | Accel FSR | Read-only | Unsigned byte (Degrees/Sec) |
0x06-0x07 | Gyro FSR | Read-only | Unsigned short(G) |
0x08 | Operational Status | Read-only | See NAVX_OP_STATUS |
0x09 | Calibration Status | Read-only | See NAVX_CAL_STATUS |
0x0A | Self-test Status | Read-only | See NAVX_SELFTEST_STATUS |
0x0B | Capability Flags (low) | Read-only | See NAVX_CAPABILITY |
0x0C | Capability Flags (high) | Read-only | “” |
0x0D-0x0F | n/a | Read-only | |
0x10 | Sensor Status (low) | Read-only | See NAVX_SENSOR_STATUS |
0x11 | Sensor Status (high) | Read-only | “” |
0x12-0x15 | Current Timestamp | Read-only | Unsigned long |
0x16-0x17 | Yaw | Read-only | Signed Packed Hundredths (Degrees) |
0x18-0x19 | Pitch | Read-only | Signed Packed Hundredths (Degrees) |
0x1A-0x1B | Roll | Read-only | Signed Packed Hundredths (Degrees) |
0x1C-0x1D | Heading | Read-only | Unsigned Packed Hundredths (Degrees) |
0x1E-0x1F | Fused Heading | Read-only | Unsigned Packed Hundredths (Degrees)) |
0x20-0x23 | Altitude | Read-only | Q16.16 – NavX-sensor Aero Edition Only (Meters) |
0x24-0x25 | Linear Acceleration (X) | Read-only | Signed Thousandths (G) |
0x26-0x27 | Linear Acceleration (Y) | Read-only | Signed Thousandths (G) |
0x28-0x29 | Linear Acceleration (Z) | Read-only | Signed Thousandths (G) |
0x2A-0x2B | Quaternion (W) | Read-only | Signed Pi Radians (Pi Radians) |
0x2C-0x2D | Quaternion (X) | Read-only | Signed Pi Radians (Pi Radians) |
0x2E-0x2F | Quaternion (Y) | Read-only | Signed Pi Radians (Pi Radians) |
0x30-0x31 | Quaternion (Z) | Read-only | Signed Pi Radians (Pi Radians) |
0x32-0x33 | MPU Temperature | Read-only | Signed Packed Hundredths (C) |
0x34-0x35 | Calibrated Gyro (X) | Read-only | Signed Short (Degrees/sec in device units) |
0x36-0x37 | Calibrated Gyro (Y) | Read-only | Signed Short (Degrees/sec in device units) |
0x38-0x39 | Calibrated Gyro (Z) | Read-only | Signed Short (Degrees/sec in device units) |
0x3A-0x3B | Calibrated Acceleration (X) | Read-only | Signed Short (G in device units) |
0x3C-0x3D | Calibrated Acceleration (Y) | Read-only | Signed Short (G in device units) |
0x3E-0x3F | Calibrated Acceleration (Z) | Read-only | Signed Short (G in device units) |
0x40-0x41 | Calibrated Magnetometer (X) | Read-only | Signed Short (uTesla in device units) |
0x42-0x43 | Calibrated Magnetometer (Y) | Read-only | Signed Short (uTesla in device units) |
0x44-0x45 | Calibrated Magnetometer (Z) | Read-only | Signed Short (uTesla in device units) |
0x46-0x49 | Barometric Pressure | Read-only | Q16.16 (millibars) |
0x4A-0x4B | Pressure Sensor Temperature | Read-only | Signed Packed Hundredths (C) |
0x4C-0x4D | Calibrated Yaw Offset | Read-only | Signed Hundredths (Degrees) |
0x4E-0x4F | Calibrated Quaternion Offset (W) | Read-only | Signed Short Ratio (Ratio) |
0x50-0x51 | Calibrated Quaternion Offset (X) | Read-only | Signed Short Ratio (Ratio) |
0x52-0x53 | Calibrated Quaternion Offset (Y) | Read-only | Signed Short Ratio (Ratio) |
0x54-0x55 | Calibrated Quaternion Offset (Z) | Read-only | Signed Short Ratio (Ratio) |
0x56 | Integration Control | Read/write | See NAVX_INTEGRATION_CTL (v1.2 firmware and higher) |
0x58-0x5B | Integrated Velocity (X) | Read-only | Q16.16 (Meters/sec) (v1.2 firmware and higher) |
0x5C-0x5F | Integrated Velocity (Y) | Read-only | Q16.16 (Meters/sec) (v1.2 firmware and higher) |
0x60-0x63 | Integrated Velocity (Z) | Read-only | Q16,16 (Meters/sec) (v1.2 firmware and higher) |
0x64-0x67 | Integrated Displacement (X) | Read-only | Q16.16 (Meters) (v1.2 firmware and higher) |
0x68-0x6B | Integrated Displacement (Y) | Read-only | Q16,16 (Meters) (v1.2 firmware and higher) |
0x6C-0x6F | Integrated Displacement (Z) | Read-only | Q16.16 (Meters) (v1.2 firmware and higher) |
NAVX_OP_STATUS
Meaning | Value |
NAVX_OP_STATUS_INITIALIZING | 0x00 |
NAVX_OP_STATUS_SELFTEST_IN_PROGRESS | 0x01 |
NAVX_OP_STATUS_ERROR | 0x02 |
NAVX_OP_STATUS_IMU_AUTOCAL_IN_PROGRESS | 0x03 |
NAVX_OP_STATUS_NORMAL | 0x04 |
NAVX_SENSOR_STATUS
Meaning | Value |
NAVX_SENSOR_STATUS_MOVING | 0x01 |
NAVX_SENSOR_STATUS_YAW_STABLE | 0x02 |
NAVX_SENSOR_STATUS_MAG_DISTURBANCE | 0x04 |
NAVX_SENSOR_STATUS_ALTITUDE_VALID | 0x08 |
NAVX_SENSOR_STATUS_SEALEVEL_PRESS_SET | 0x10 |
NAVX_SENSOR_STATUS_FUSED_HEADING_VALID | 0x20 |
NAVX_CAL_STATUS
Meaning | Value |
NAVX_CAL_STATUS_IMU_CAL_INPROGRESS | 0x00 |
NAVX_CAL_STATUS_IMU_CAL_ACCUMULATE | 0x01 |
NAVX_CAL_STATUS_IMU_CAL_COMPLETE | 0x02 |
NAVX_CAL_STATUS_MAG_CAL_COMPLETE | 0x04 |
NAVX_CAL_STATUS_BARO_CAL_COMPLETE | 0x08 |
NAVX_SELFTEST_STATUS
Meaning | Value |
NAVX_SELFTEST_STATUS_COMPLETE | 0x80 |
NAVX_SELFTEST_RESULT_GYRO_PASSED | 0x01 |
NAVX_SELFTEST_RESULT_ACCEL_PASSED | 0x02 |
NAVX_SELFTEST_RESULT_MAG_PASSED | 0x04 |
NAVX_SELFTEST_RESULT_BARO_PASSED | 0x08 |
NAVX_CAPABILITY
Meaning | Value |
NAVX_CAPABILITY_FLAG_OMNIMOUNT | 0x04 |
NAVX_CAPABILITY_FLAG_OMNIMOUNT_CONFIG_MASK | 0x38 |
NAVX_CAPABILITY_FLAG_VEL_AND_DISP | 0x40 |
NAVX_CAPABILITY_FLAG_VEL_AND_DISP | 0x80 |
NAVX_OMNIMOUNT_CONFIG
Meaning | Value |
OMNIMOUNT_DEFAULT (Z Axis, Up) | 0x00 |
OMNIMOUNT_YAW_X_UP | 0x01 |
OMNIMOUNT_YAW_X_DOWN | 0x02 |
OMNIMOUNT_YAW_Y_UP | 0x03 |
OMNIMOUNT_YAW_Y_DOWN | 0x04 |
OMNIMOUNT_YAW_Z_UP | 0x05 |
OMNIMOUNT_YAW_Z_DOWN | 0x06 |
NAVX_INTEGRATION_CTL
Meaning | Value |
NAVX_INTEGRATION_CTL_RESET_VEL_X | 0x01 |
NAVX_INTEGRATION_CTL_RESET_VEL_Y | 0x02 |
NAVX_INTEGRATION_CTL_RESET_VEL_X | 0x04 |
NAVX_INTEGRATION_CTL_RESET_DISP_X | 0x08 |
NAVX_INTEGRATION_CTL_RESET_DISP_Y | 0x10 |
NAVX_INTEGRATION_CTL_RESET_DISP_X | 0x20 |
NAVX_INTEGRATION_CTL_RESET_YAW | 0x80 |