IMU¶
IMU (intertial measurement unit) node can be used to receive data from the IMU chip on the device. Our OAK devices use either:
BNO085 (datasheet here) 9-axis sensor, combining accelerometer, gyroscope, and magnetometer. It also does sensor fusion on the (IMU) chip itself. We have efficiently integrated this driver into the DepthAI.
BMI270 6-axis sensor, combining accelerometer and gyroscope
. The IMU chip is connected to the RVC over SPI.
How to place it¶
pipeline = dai.Pipeline()
imu = pipeline.create(dai.node.IMU)
dai::Pipeline pipeline;
auto imu = pipeline.create<dai::node::IMU>();
Inputs and Outputs¶
┌──────────────┐
│ │
│ │ out
│ IMU ├─────────►
│ │
│ │
└──────────────┘
Message types
out
- IMUData
Limitations¶
For BNO086, gyroscope frequency above 400Hz can produce some jitter from time to time due to sensor HW limitation.
Maximum frequencies: 500 Hz raw accelerometer, 1000 Hz raw gyroscope values individually, and 500Hz combined (synced) output. You can obtain the combined synced 500Hz output with
imu.enableIMUSensor([dai.IMUSensor.ACCELEROMETER_RAW, dai.IMUSensor.GYROSCOPE_RAW], 500)
.
Usage¶
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)
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);
IMU devices¶
List of devices that have an IMU sensor on-board:
OAK-D Pro (All varients)
OAK-D S2 (All varients)
OAK-D S2 PoE (All varients)
OAK-D Pro PoE (All varients)
IMU sensors¶
When enabling the IMU sensors (imu.enableIMUSensor()
), you can select between the following sensors:
ACCELEROMETER_RAW
ACCELEROMETER
LINEAR_ACCELERATION
GRAVITY
GYROSCOPE_RAW
GYROSCOPE_CALIBRATED
GYROSCOPE_UNCALIBRATED
MAGNETOMETER_RAW
MAGNETOMETER_CALIBRATED
MAGNETOMETER_UNCALIBRATED
ROTATION_VECTOR
GAME_ROTATION_VECTOR
GEOMAGNETIC_ROTATION_VECTOR
ARVR_STABILIZED_ROTATION_VECTOR
ARVR_STABILIZED_GAME_ROTATION_VECTOR
Here are descriptions of all sensors:
-
class
depthai.
IMUSensor
Available IMU sensors. More details about each sensor can be found in the datasheet:
https://www.ceva-dsp.com/wp-content/uploads/2019/10/BNO080_085-Datasheet.pdf
Members:
ACCELEROMETER_RAW : Section 2.1.1
Acceleration of the device without any postprocessing, straight from the sensor. Units are [m/s^2]
ACCELEROMETER : Section 2.1.1
Acceleration of the device including gravity. Units are [m/s^2]
LINEAR_ACCELERATION : Section 2.1.1
Acceleration of the device with gravity removed. Units are [m/s^2]
GRAVITY : Section 2.1.1
Gravity. Units are [m/s^2]
GYROSCOPE_RAW : Section 2.1.2
The angular velocity of the device without any postprocessing, straight from the sensor. Units are [rad/s]
GYROSCOPE_CALIBRATED : Section 2.1.2
The angular velocity of the device. Units are [rad/s]
GYROSCOPE_UNCALIBRATED : Section 2.1.2
Angular velocity without bias compensation. Units are [rad/s]
MAGNETOMETER_RAW : Section 2.1.3
Magnetic field measurement without any postprocessing, straight from the sensor. Units are [uTesla]
MAGNETOMETER_CALIBRATED : Section 2.1.3
The fully calibrated magnetic field measurement. Units are [uTesla]
MAGNETOMETER_UNCALIBRATED : Section 2.1.3
The magnetic field measurement without hard-iron offset applied. Units are [uTesla]
ROTATION_VECTOR : Section 2.2
The rotation vector provides an orientation output that is expressed as a quaternion referenced to magnetic north and gravity. It is produced by fusing the outputs of the accelerometer, gyroscope and magnetometer. The rotation vector is the most accurate orientation estimate available. The magnetometer provides correction in yaw to reduce drift and the gyroscope enables the most responsive performance.
GAME_ROTATION_VECTOR : Section 2.2
The game rotation vector is an orientation output that is expressed as a quaternion with no specific reference for heading, while roll and pitch are referenced against gravity. It is produced by fusing the outputs of the accelerometer and the gyroscope (i.e. no magnetometer). The game rotation vector does not use the magnetometer to correct the gyroscopes drift in yaw. This is a deliberate omission (as specified by Google) to allow gaming applications to use a smoother representation of the orientation without the jumps that an instantaneous correction provided by a magnetic field update could provide. Long term the output will likely drift in yaw due to the characteristics of gyroscopes, but this is seen as preferable for this output versus a corrected output.
GEOMAGNETIC_ROTATION_VECTOR : Section 2.2
The geomagnetic rotation vector is an orientation output that is expressed as a quaternion referenced to magnetic north and gravity. It is produced by fusing the outputs of the accelerometer and magnetometer. The gyroscope is specifically excluded in order to produce a rotation vector output using less power than is required to produce the rotation vector of section 2.2.4. The consequences of removing the gyroscope are: Less responsive output since the highly dynamic outputs of the gyroscope are not used More errors in the presence of varying magnetic fields.
ARVR_STABILIZED_ROTATION_VECTOR : Section 2.2
Estimates of the magnetic field and the roll/pitch of the device can create a potential correction in the rotation vector produced. For applications (typically augmented or virtual reality applications) where a sudden jump can be disturbing, the output is adjusted to prevent these jumps in a manner that takes account of the velocity of the sensor system.
ARVR_STABILIZED_GAME_ROTATION_VECTOR : Section 2.2
While the magnetometer is removed from the calculation of the game rotation vector, the accelerometer itself can create a potential correction in the rotation vector produced (i.e. the estimate of gravity changes). For applications (typically augmented or virtual reality applications) where a sudden jump can be disturbing, the output is adjusted to prevent these jumps in a manner that takes account of the velocity of the sensor system. This process is called AR/VR stabilization.
Examples of functionality¶
Reference¶
-
class
depthai.node.
IMU
IMU node for BNO08X.
-
class
Connection
Connection between an Input and Output
-
class
Id
Node identificator. Unique for every node on a single Pipeline
-
enableFirmwareUpdate
(self: depthai.node.IMU, arg0: bool) → None
-
enableIMUSensor
(*args, **kwargs) Overloaded function.
enableIMUSensor(self: depthai.node.IMU, sensorConfig: depthai.IMUSensorConfig) -> None
Enable a new IMU sensor with explicit configuration
enableIMUSensor(self: depthai.node.IMU, sensorConfigs: List[depthai.IMUSensorConfig]) -> None
Enable a list of IMU sensors with explicit configuration
enableIMUSensor(self: depthai.node.IMU, sensor: depthai.IMUSensor, reportRate: int) -> None
Enable a new IMU sensor with default configuration
enableIMUSensor(self: depthai.node.IMU, sensors: List[depthai.IMUSensor], reportRate: int) -> None
Enable a list of IMU sensors with default configuration
-
getAssetManager
(*args, **kwargs) Overloaded function.
getAssetManager(self: depthai.Node) -> depthai.AssetManager
Get node AssetManager as a const reference
getAssetManager(self: depthai.Node) -> depthai.AssetManager
Get node AssetManager as a const reference
-
getBatchReportThreshold
(self: depthai.node.IMU) → int Above this packet threshold data will be sent to host, if queue is not blocked
-
getInputRefs
(*args, **kwargs) Overloaded function.
getInputRefs(self: depthai.Node) -> List[depthai.Node.Input]
Retrieves reference to node inputs
getInputRefs(self: depthai.Node) -> List[depthai.Node.Input]
Retrieves reference to node inputs
-
getInputs
(self: depthai.Node) → List[depthai.Node.Input] Retrieves all nodes inputs
-
getMaxBatchReports
(self: depthai.node.IMU) → int Maximum number of IMU packets in a batch report
-
getName
(self: depthai.Node) → str Retrieves nodes name
-
getOutputRefs
(*args, **kwargs) Overloaded function.
getOutputRefs(self: depthai.Node) -> List[depthai.Node.Output]
Retrieves reference to node outputs
getOutputRefs(self: depthai.Node) -> List[depthai.Node.Output]
Retrieves reference to node outputs
-
getOutputs
(self: depthai.Node) → List[depthai.Node.Output] Retrieves all nodes outputs
-
getParentPipeline
(*args, **kwargs) Overloaded function.
getParentPipeline(self: depthai.Node) -> depthai.Pipeline
getParentPipeline(self: depthai.Node) -> depthai.Pipeline
-
property
id
Id of node
-
property
out
Outputs IMUData message that carries IMU packets.
-
setBatchReportThreshold
(self: depthai.node.IMU, batchReportThreshold: int) → None Above this packet threshold data will be sent to host, if queue is not blocked
-
setMaxBatchReports
(self: depthai.node.IMU, maxBatchReports: int) → None Maximum number of IMU packets in a batch report
-
class
-
class
dai::node
::
IMU
: public dai::NodeCRTP<Node, IMU, IMUProperties>¶ IMU node for BNO08X.
Public Functions
Constructs IMU node.
-
void
enableIMUSensor
(IMUSensorConfig sensorConfig)¶ Enable a new IMU sensor with explicit configuration
-
void
enableIMUSensor
(const std::vector<IMUSensorConfig> &sensorConfigs)¶ Enable a list of IMU sensors with explicit configuration
-
void
enableIMUSensor
(IMUSensor sensor, uint32_t reportRate)¶ Enable a new IMU sensor with default configuration
-
void
enableIMUSensor
(const std::vector<IMUSensor> &sensors, uint32_t reportRate)¶ Enable a list of IMU sensors with default configuration
-
void
setBatchReportThreshold
(std::int32_t batchReportThreshold)¶ Above this packet threshold data will be sent to host, if queue is not blocked
-
std::int32_t
getBatchReportThreshold
() const¶ Above this packet threshold data will be sent to host, if queue is not blocked
-
void
setMaxBatchReports
(std::int32_t maxBatchReports)¶ Maximum number of IMU packets in a batch report
-
void
enableFirmwareUpdate
(bool enable)¶
Public Members
-
Output
out
= {*this, "out", Output::Type::MSender, {{DatatypeEnum::IMUData, false}}}¶
Public Static Attributes
-
static constexpr const char *
NAME
= "IMU"¶
Got questions?
We’re always happy to help with code or other questions you might have.