diff --git a/docs/source/components/messages/imu_data.rst b/docs/source/components/messages/imu_data.rst new file mode 100644 index 000000000..caee03085 --- /dev/null +++ b/docs/source/components/messages/imu_data.rst @@ -0,0 +1,26 @@ +IMUData +======= + +IMU data message is created by the :ref:`IMU` node. + +Reference +######### + +.. tabs:: + + .. tab:: Python + + .. autoclass:: depthai.IMUData + :members: + :inherited-members: + :noindex: + + .. tab:: C++ + + .. doxygenclass:: dai::IMUData + :project: depthai-core + :members: + :private-members: + :undoc-members: + +.. include:: ../../includes/footer-short.rst diff --git a/docs/source/components/nodes/imu.rst b/docs/source/components/nodes/imu.rst new file mode 100644 index 000000000..ba68f9336 --- /dev/null +++ b/docs/source/components/nodes/imu.rst @@ -0,0 +1,135 @@ +IMU +=== + +IMU (`intertial measurement unit `__) node can be used to receive data from the IMU chip on the device. +Our DepthAI devices use `BNO085 `__ 9-axis sensor (`datasheet here `__) +that supports sensor fusion on the (IMU) chip itself. The IMU chip is connected to the Myriad X (VPU) over SPI (we have integrated +`this driver `__ to the DepthAI). + + +How to place it +############### + +.. tabs:: + + .. code-tab:: py + + pipeline = dai.Pipeline() + imu = pipeline.create(dai.node.IMU) + + .. code-tab:: c++ + + dai::Pipeline pipeline; + auto imu = pipeline.create(); + + +Inputs and Outputs +################## + +.. code-block:: + + ┌──────────────┐ + │ │ + │ │ out + │ IMU ├─────────► + │ │ + │ │ + └──────────────┘ + +**Message types** + +- :code:`out` - :ref:`IMUData` + +Maximum frequencies +################### + +Maximum output frequencies are 500 Hz raw accelerometer, 1000 Hz raw gyroscope values individually, and 500 Hz combined (synced) output. +You can obtain the combined (synced) 500 Hz output with :code:`imu.enableIMUSensor([dai.IMUSensor.RAW_ACCELEROMETER, dai.IMUSensor.RAW_GYROSCOPE], 500)`. + +Usage +##### + +.. tabs:: + + .. code-tab:: py + + pipeline = dai.Pipeline() + imu = pipeline.create(dai.node.IMU) + + # enable RAW_ACCELEROMETER and RAW_GYROSCOPE at 100 hz rate + imu.enableIMUSensor([dai.IMUSensor.RAW_ACCELEROMETER, dai.IMUSensor.RAW_GYROSCOPE], 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) + + .. code-tab:: c++ + + dai::Pipeline pipeline; + auto imu = pipeline.create(); + + // enable RAW_ACCELEROMETER and RAW_GYROSCOPE at 100 hz rate + imu->enableIMUSensor({dai::IMUSensor::RAW_ACCELEROMETER, dai::IMUSensor::RAW_GYROSCOPE}, 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 sensors +########### + +When enabling the IMU sensors (:code:`imu.enableIMUSensor()`), you can select between the following sensors: + +- :code:`ACCELEROMETER_RAW` +- :code:`ACCELEROMETER` +- :code:`LINEAR_ACCELERATION` +- :code:`GRAVITY` +- :code:`GYROSCOPE_RAW` +- :code:`GYROSCOPE_CALIBRATED` +- :code:`GYROSCOPE_UNCALIBRATED` +- :code:`MAGNETOMETER_RAW` +- :code:`MAGNETOMETER_CALIBRATED` +- :code:`MAGNETOMETER_UNCALIBRATED` +- :code:`ROTATION_VECTOR` +- :code:`GAME_ROTATION_VECTOR` +- :code:`GEOMAGNETIC_ROTATION_VECTOR` +- :code:`ARVR_STABILIZED_ROTATION_VECTOR` +- :code:`ARVR_STABILIZED_GAME_ROTATION_VECTOR` + +Here are **descriptions of all sensors**: + +.. autoclass:: depthai.IMUSensor + :noindex: + +Examples of functionality +######################### + +- :ref:`IMU Accelerometer & Gyroscope` +- :ref:`IMU Rotation Vector` + +Reference +######### + +.. tabs:: + + .. tab:: Python + + .. autoclass:: depthai.node.IMU + :members: + :inherited-members: + :noindex: + + .. tab:: C++ + + .. doxygenclass:: dai::node::IMU + :project: depthai-core + :members: + :private-members: + :undoc-members: + +.. include:: ../../includes/footer-short.rst diff --git a/docs/source/samples/imu_accelerometer_gyroscope.rst b/docs/source/samples/imu_accelerometer_gyroscope.rst index b421f2bc1..bb82c0527 100644 --- a/docs/source/samples/imu_accelerometer_gyroscope.rst +++ b/docs/source/samples/imu_accelerometer_gyroscope.rst @@ -7,6 +7,19 @@ Returns acceleration [m/s^2] and angular velocity [rad/s]. Demo #### +Example script output + +.. code-block:: + + ~/depthai-python/examples$ python3 imu_gyroscope_accelerometer.py + Accelerometer timestamp: 0.000 ms + Accelerometer [m/s^2]: x: -0.162806 y: 6.445191 z: 3.189077 + Gyroscope timestamp: 1.642 ms + Gyroscope [rad/s]: x: -0.040480 y: 0.088417 z: -0.168312 + Accelerometer timestamp: 2.073 ms + Accelerometer [m/s^2]: x: -0.229843 y: 6.263232 z: 3.572149 + Gyroscope timestamp: 3.663 ms + Gyroscope [rad/s]: x: -0.072438 y: 0.115049 z: -0.350472 Setup ##### diff --git a/docs/source/samples/imu_rotation_vector.rst b/docs/source/samples/imu_rotation_vector.rst index a9366becb..6e284df89 100644 --- a/docs/source/samples/imu_rotation_vector.rst +++ b/docs/source/samples/imu_rotation_vector.rst @@ -7,6 +7,20 @@ Returns quaternion. Demo #### +Example script output + +.. code-block:: + + ~/depthai-python/examples$ python3 imu_rotation_vector.py + Rotation vector timestamp: 0.000 ms + Quaternion: i: 0.089355 j: 0.355103 k: 0.034058 real: 0.929932 + Accuracy (rad): 3.141602 + Rotation vector timestamp: 3.601 ms + Quaternion: i: 0.088928 j: 0.354004 k: 0.036560 real: 0.930298 + Accuracy (rad): 3.141602 + Rotation vector timestamp: 6.231 ms + Quaternion: i: 0.094604 j: 0.344543 k: 0.040955 real: 0.933105 + Accuracy (rad): 3.141602 Setup #####