# IMU

IMU ([inertial measurement unit](https://en.wikipedia.org/wiki/Inertial_measurement_unit)) node can be used to receive data from
the IMU chip on the device.

Luxonis devices use different IMU stacks depending on platform generation:

 * RVC2 devices use either [BNO08X](https://docs.luxonis.com/hardware/platform/sensors/imu/bno08x.md) or
   [BMI270](https://docs.luxonis.com/hardware/platform/sensors/imu/bmi270.md)
 * RVC4 devices use [LSM6DSV](https://docs.luxonis.com/hardware/platform/sensors/imu/lsm6dsv.md) together with an
   [AK09919](https://docs.luxonis.com/hardware/platform/sensors/imu/ak09919.md) magnetometer.

The IMU chip is connected to the [RVC](https://docs.luxonis.com/hardware/platform/rvc/rvc2.md#rvc2) over SPI. See [OAK Hardware
documentation](https://docs.luxonis.com/hardware.md) to check whether your OAK camera has IMU integrated.

> **Looking for the conceptual docs?**
> For sensor families, output semantics, reference frames, factory calibration, and noise characterization, see the
> [IMU hardware reference](https://docs.luxonis.com/hardware/platform/sensors/imu.md)
> . For practical usage, see the IMU examples below.

## How to place it

#### Python

```python
pipeline = dai.Pipeline()
imu = pipeline.create(dai.node.IMU)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto imu = pipeline.create<dai::node::IMU>();
```

## Inputs and Outputs

## Pipeline flow

The usual IMU node flow is:

 1. Create dai::node::IMU
 2. Enable one or more IMUSensor reports at a requested rate
 3. Configure batching with setBatchReportThreshold() and setMaxBatchReports()
 4. Consume IMUData packets from the host output queue

## Limitations

 * On RVC2 devices with BNO08X, gyroscope frequencies above 400 Hz can produce occasional jitter due to sensor hardware
   limitations.

## Requested report rate

imu.enableIMUSensor(..., reportRate) accepts a requested report rate in Hz.

Actual runtime behavior depends on the IMU and platform:

 * On RVC2 devices using BNO08X, requested rates round up to the next supported rate.
 * On RVC2 devices using BMI270, requested rates round down to the next supported rate. Requests above 400 Hz currently top out
   around 250 Hz.
 * On RVC4 devices using LSM6DSV + AK09919, treat validated runtime rates as platform-specific rather than assuming the silicon
   max ODR maps directly to the host stream rate.

For detailed per-sensor runtime behavior and hardware characteristics, see the [IMU hardware
reference](https://docs.luxonis.com/hardware/platform/sensors/imu.md).

### High-rate raw streaming used in examples

The current depthai-core IMU examples and tests use the following raw-stream rates for high-rate capture:

 * ACCELEROMETER_RAW at 480 Hz
 * GYROSCOPE_RAW at 400 Hz

## Batching

The IMU node batches packets before sending them to the host.

 * setBatchReportThreshold(N) sets the minimum number of IMU packets that should be ready before the device is allowed to send a
   batch
 * setMaxBatchReports(M) sets the maximum number of packets included in one batch

Higher batching can reduce host overhead and help when USB bandwidth or host scheduling becomes the bottleneck.

## Packet fields and report semantics

Each IMUData message contains one or more IMUPacket entries. Each packet only carries the fields for the reports that were enabled
in the node configuration.

Typical fields include:

 * acceleroMeter
 * gyroscope
 * magneticField
 * rotationVector

Use the report families like this:

 * *_RAW: direct sensor output in the sensor-native frame
 * *_UNCALIBRATED: rotated into the Luxonis RDF frame using imuExtrinsics, without IMU calibration parameters applied
 * *_CALIBRATED: rotated into the Luxonis RDF frame and corrected using IMU calibration parameters
 * fused outputs such as ROTATION_VECTOR and GAME_ROTATION_VECTOR: forwarded from the sensor's internal processing path

## Usage

#### Python

```python
pipeline = dai.Pipeline()
imu = pipeline.create(dai.node.IMU)

# enable ACCELEROMETER_RAW and GYROSCOPE_RAW at 100 hz rate
imu.enableIMUSensor([dai.IMUSensor.ACCELEROMETER_RAW, dai.IMUSensor.GYROSCOPE_RAW], 100)
# above this threshold packets will be sent in batch of X, if the host is not blocked and USB bandwidth is available
imu.setBatchReportThreshold(1)
# maximum number of IMU packets in a batch, if it's reached device will block sending until host can receive it
# if lower or equal to batchReportThreshold then the sending is always blocking on device
# useful to reduce device's CPU load  and number of lost packets, if CPU load is high on device side due to multiple nodes
imu.setMaxBatchReports(10)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto imu = pipeline.create<dai::node::IMU>();

// enable ACCELEROMETER_RAW and GYROSCOPE_RAW at 100 hz rate
imu->enableIMUSensor({dai::IMUSensor::ACCELEROMETER_RAW, dai::IMUSensor::GYROSCOPE_RAW}, 100);
// above this threshold packets will be sent in batch of X, if the host is not blocked and USB bandwidth is available
imu->setBatchReportThreshold(1);
// maximum number of IMU packets in a batch, if it's reached device will block sending until host can receive it
// if lower or equal to batchReportThreshold then the sending is always blocking on device
// useful to reduce device's CPU load  and number of lost packets, if CPU load is high on device side due to multiple nodes
imu->setMaxBatchReports(10);
```

## Report availability by hardware

> **Current public API scope**
> The current
> `depthai-core`
> IMU enum and docstrings are still BNO08X-oriented. In the bindings, the node is still documented as
> `IMU node for BNO08X`
> , so fused and processed report coverage should be read together with the hardware docs and validated on the target device when
the sensor path is not BNO08X.

| Report family | `IMUSensor` values | BNO08X | BMI270 | LSM6DSV | AK09919 | Notes |
| --- | --- | --- | --- | --- | --- | --- |
| Raw acceleration | `ACCELEROMETER_RAW` | Yes | Yes | Yes | No | Raw accelerometer stream |
| Accelerometer in Luxonis frame, without IMU calibration parameters | `ACCELEROMETER_UNCALIBRATED` | Yes | Yes | Yes | No | `RAW
-> UNCALIBRATED` applies `imuExtrinsics`. This is the unified IMU-frame accelerometer path. |
| Accelerometer in Luxonis frame, with IMU calibration parameters | `ACCELEROMETER_CALIBRATED` | Yes | Yes | Yes | No | Requires
IMU calibration parameters to be present in the runtime calibration payload. |
| Raw angular velocity | `GYROSCOPE_RAW` | Yes | Yes | Yes | No | Raw gyroscope stream |
| Gyroscope in Luxonis frame, without IMU calibration parameters | `GYROSCOPE_UNCALIBRATED` | Yes | Yes | Yes | No | `RAW ->
UNCALIBRATED` applies `imuExtrinsics`. On older devices this is expected to work out of the box. |
| Gyroscope in Luxonis frame, with IMU calibration parameters | `GYROSCOPE_CALIBRATED` | Yes | Yes | Yes | No | Requires IMU
calibration parameters to be present in the runtime calibration payload. |
| Raw magnetic field | `MAGNETOMETER_RAW` | Yes | No | No | Yes | On RVC4, raw magnetometer data comes from the AK09919 companion
sensor. |
| Processed magnetic field | `MAGNETOMETER_CALIBRATED`, `MAGNETOMETER_UNCALIBRATED` | Yes | No | No | Validate on target hardware
| Public enum/docstrings are still BNO08X-shaped for processed magnetometer outputs. |
| Derived acceleration outputs | `LINEAR_ACCELERATION`, `GRAVITY` | Yes | No | Validate on target hardware | No | BNO08X exposes
these directly. For non-BNO paths, validate availability on the target device and branch. |
| Fused orientation outputs | `ROTATION_VECTOR`, `GAME_ROTATION_VECTOR`, `GEOMAGNETIC_ROTATION_VECTOR`,
`ARVR_STABILIZED_ROTATION_VECTOR`, `ARVR_STABILIZED_GAME_ROTATION_VECTOR` | Yes | No | Validate on target hardware | No standalone
| These are sensor-fusion outputs, not host-side fusion done by the IMU node. |

## Calibration and extrinsics

Use device.readCalibration() to read the factory calibration payload from the device. Use device.getCalibration() and
device.setCalibration() when working with runtime calibration overrides.

For the processed inertial outputs, use this model:

 * RAW -> UNCALIBRATED: align the sensor-native frame into the Luxonis RDF frame using imuExtrinsics
 * UNCALIBRATED -> CALIBRATED: apply the accelerometer or gyroscope calibration set in the IMU calibration parameters
 * ACCELEROMETER_UNCALIBRATED and GYROSCOPE_UNCALIBRATED therefore share the unified IMU-frame path
 * ACCELEROMETER_CALIBRATED and GYROSCOPE_CALIBRATED add the runtime calibration correction on top of that

### Processed output transforms

#### RAW -> UNCALIBRATED

```python
import depthai as dai
import numpy as np

with dai.Pipeline() as pipeline:
    imu = pipeline.create(dai.node.IMU)
    imu.enableIMUSensor(dai.IMUSensor.ACCELEROMETER_RAW, 100)
    imu_q = imu.out.createOutputQueue(maxSize=10, blocking=False)

    device = pipeline.getDefaultDevice()
    calib = device.readCalibration()
    imu_to_cam = np.array(calib.getImuToCameraExtrinsics(dai.CameraBoardSocket.CAM_A, False))
    R_imu_to_cam = imu_to_cam[:3, :3]

    pipeline.start()
    pkt = imu_q.get().packets[0]
    raw = np.array([pkt.acceleroMeter.x, pkt.acceleroMeter.y, pkt.acceleroMeter.z])
    uncalibrated = R_imu_to_cam @ raw
```

#### UNCALIBRATED -> CALIBRATED

```python
import depthai as dai
import numpy as np

imu_calibration = [
    [1.0, 0.0, 0.0, 0.125],
    [0.0, 1.0, 0.0, 0.000],
    [0.0, 0.0, 1.0, 0.000],
]

with dai.Pipeline() as pipeline:
    imu = pipeline.create(dai.node.IMU)
    imu.enableIMUSensor(dai.IMUSensor.ACCELEROMETER_UNCALIBRATED, 100)
    imu_q = imu.out.createOutputQueue(maxSize=10, blocking=False)

    pipeline.start()
    pkt = imu_q.get().packets[0]
    uncalibrated = np.array([pkt.acceleroMeter.x, pkt.acceleroMeter.y, pkt.acceleroMeter.z])

    calibration = np.array(imu_calibration)
    calibrated = calibration[:, :3] @ uncalibrated + calibration[:, 3]
```

## Reading multiple IMU streams

If the target hardware exposes the selected reports, you can enable multiple IMU report families and read only the fields that
were requested.

#### Python

```python
import depthai as dai

with dai.Pipeline() as pipeline:
    imu = pipeline.create(dai.node.IMU)

    imu.enableIMUSensor(dai.IMUSensor.ACCELEROMETER_RAW, 100)
    imu.enableIMUSensor(dai.IMUSensor.GYROSCOPE_RAW, 100)
    imu.enableIMUSensor(dai.IMUSensor.MAGNETOMETER_RAW, 100)

    imu.setBatchReportThreshold(1)
    imu.setMaxBatchReports(10)

    imu_q = imu.out.createOutputQueue(maxSize=50, blocking=False)

    pipeline.start()
    while pipeline.isRunning():
        imu_data = imu_q.get()
        for pkt in imu_data.packets:
            a = pkt.acceleroMeter
            g = pkt.gyroscope
            m = pkt.magneticField
```

#### C++

```cpp
#include "depthai/depthai.hpp"

int main() {
    dai::Pipeline pipeline;
    auto imu = pipeline.create<dai::node::IMU>();

    imu->enableIMUSensor(dai::IMUSensor::ACCELEROMETER_RAW, 100);
    imu->enableIMUSensor(dai::IMUSensor::GYROSCOPE_RAW, 100);
    imu->enableIMUSensor(dai::IMUSensor::MAGNETOMETER_RAW, 100);

    imu->setBatchReportThreshold(1);
    imu->setMaxBatchReports(10);

    auto imuQ = imu->out.createOutputQueue(50, false);

    pipeline.start();
    while(pipeline.isRunning()) {
        auto data = imuQ->get<dai::IMUData>();
        for(const auto& pkt : data->packets) {
            const auto& a = pkt.acceleroMeter;
            const auto& g = pkt.gyroscope;
            const auto& m = pkt.magneticField;
        }
    }
}
```

## Examples of functionality

 * [IMU Accelerometer & Gyroscope](https://docs.luxonis.com/software-v3/depthai/examples/imu/imu_accelerometer_gyroscope.md)
 * [IMU Rotation Vector](https://docs.luxonis.com/software-v3/depthai/examples/imu_rotation_vector.md)
 * [IMU and Video Sync](https://docs.luxonis.com/software-v3/depthai/examples/imu_video_sync.md)

## Reference

### dai::node::IMU

Kind: class

IMU node for BNO08X.

#### Output out

Kind: variable

Outputs IMUData message that carries IMU packets.

#### Input mockIn

Kind: variable

Mock IMU data for replaying recorded data

#### void enableIMUSensor(IMUSensorConfig sensorConfig)

Kind: function

Enable a new IMU sensor with explicit configuration

#### void enableIMUSensor(const std::vector< IMUSensorConfig > & sensorConfigs)

Kind: function

Enable a list of IMU sensors with explicit configuration

#### void enableIMUSensor(IMUSensor sensor, uint32_t reportRate)

Kind: function

Enable a new IMU sensor with default configuration

#### void enableIMUSensor(const std::vector< IMUSensor > & sensors, uint32_t reportRate)

Kind: function

Enable a list of IMU sensors with default configuration

#### void setBatchReportThreshold(std::int32_t batchReportThreshold)

Kind: function

Above this packet threshold data will be sent to host, if queue is not blocked

#### std::int32_t getBatchReportThreshold()

Kind: function

Above this packet threshold data will be sent to host, if queue is not blocked

#### void setMaxBatchReports(std::int32_t maxBatchReports)

Kind: function

Maximum number of IMU packets in a batch report

#### std::int32_t getMaxBatchReports()

Kind: function

Maximum number of IMU packets in a batch report

#### void enableFirmwareUpdate(bool enable)

Kind: function

Whether to perform firmware update or not. Default value: false.

#### DeviceNodeCRTP()

Kind: function

#### DeviceNodeCRTP(const std::shared_ptr< Device > & device)

Kind: function

#### DeviceNodeCRTP(std::unique_ptr< Properties > props)

Kind: function

#### DeviceNodeCRTP(std::unique_ptr< Properties > props, bool confMode)

Kind: function

#### DeviceNodeCRTP(const std::shared_ptr< Device > & device, std::unique_ptr< Properties > props, bool confMode)

Kind: function

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
