Skip to content

Commit

Permalink
Docs/release 25 (#997)
Browse files Browse the repository at this point in the history
* Initial docs update for v2.25

* Added pcl example docs

* Adding pointcloud control example

* Updating pointcloud example
  • Loading branch information
jakaskerl authored Mar 14, 2024
1 parent a6a24d6 commit cf41a43
Show file tree
Hide file tree
Showing 13 changed files with 536 additions and 3 deletions.
Binary file modified docs/source/_static/images/components/clock-syncing.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
8 changes: 6 additions & 2 deletions docs/source/components/device.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,9 +67,13 @@ Device clocks are synced at below 500µs accuracy for PoE cameras, and below 200

.. image:: /_static/images/components/clock-syncing.png

A graph representing the accuracy of the device clock with respect to the host clock. We had 3 devices connected (OAK PoE cameras), all were hardware synchronized using `FSYNC Y-adapter <https://docs.luxonis.com/projects/hardware/en/latest/pages/FSYNC_Yadapter/>`__.
Above is a graph representing the accuracy of the device clock with respect to the host clock. We had 3 devices connected (OAK PoE cameras), all were hardware synchronized using `FSYNC Y-adapter <https://docs.luxonis.com/projects/hardware/en/latest/pages/FSYNC_Yadapter/>`__.
Raspberry Pi (the host) had an interrupt pin connected to the FSYNC line, so at the start of each frame the interrupt happened and the host clock was recorded. Then we compared frame (synced) timestamps with
host timestamps and computed the standard deviation. For the histogram above we ran this test for approximately 3 hours.
host timestamps and computed the standard deviation. For the histogram above we ran this test for approximately 3 hours.

Below is a graph representing the difference between the device and host clock. The graph shows the difference between the device and host clock over time. The graph is a result of the same test as the previous one.

.. image:: /_static/images/components/timestamp-difference.png

.. code-block:: python
Expand Down
98 changes: 98 additions & 0 deletions docs/source/components/messages/pointcloud_config.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
PointCloudConfig
================

`PointCloudConfig` is a configuration class used to adjust settings for point cloud generation within the DepthAI ecosystem. It allows users to configure properties such as sparsity and transformation matrices, which are crucial for tailoring the point cloud data to specific application requirements.

Configuration Options
######################

- **Sparsity**: Determines whether the generated point cloud should be sparse. Sparse point clouds may omit points based on certain criteria, such as depth value thresholds, to reduce data volume and processing requirements.
- **Transformation Matrix**: Applies a transformation matrix to the point cloud data, enabling rotations, translations, and scaling to align the point cloud with a world or application-specific coordinate system.

Usage
#####

Configuring `PointCloudConfig` allows for precise control over the generation of point cloud data. Here's an example of how to configure and apply `PointCloudConfig` in a DepthAI application:

.. tabs::

.. code-tab:: py

import depthai as dai

# Create pipeline
pipeline = dai.Pipeline()

# Create PointCloud node
pointCloud = pipeline.create(dai.node.PointCloud)

pointCloud.initialConfig.setSparse(True) # Enable sparse point cloud generation

# Define a transformation matrix
transformationMatrix = [
[1.0, 0.0, 0.0, 0.0],
[0.0, 1.0, 0.0, 0.0],
[0.0, 0.0, 1.0, 0.0],
[0.0, 0.0, 0.0, 1.0]
]
pointCloud.initialConfig.setTransformationMatrix(transformationMatrix) # Apply transformation matrix

# Further pipeline setup and execution...

.. code-tab:: c++

#include "depthai/depthai.hpp"

int main() {
// Create pipeline
dai::Pipeline pipeline;

// Create PointCloud node
auto pointCloud = pipeline.create<dai::node::PointCloud>();

pointCloud->initialConfig.setSparse(true); // Enable sparse point cloud generation

// Define a transformation matrix
std::vector<std::vector<float>> transformationMatrix = {
{1.0, 0.0, 0.0, 0.0},
{0.0, 1.0, 0.0, 0.0},
{0.0, 0.0, 1.0, 0.0},
{0.0, 0.0, 0.0, 1.0}
};
pointCloud->initialConfig.setTransformationMatrix(transformationMatrix); // Apply transformation matrix

// Further pipeline setup and execution...

return 0;
}

This example demonstrates initializing `PointCloudConfig`, setting it to generate sparse point clouds, and applying a transformation matrix. This configuration is then applied to a `PointCloud` node within the DepthAI pipeline.

Examples of Functionality
#########################

- **3D Object Localization**: Adjusting the transformation matrix to align point clouds with a known coordinate system for precise object placement.
- **Scene Optimization**: Utilizing sparse point clouds for efficient processing in large-scale or complex scenes.
- **Data Alignment**: Applying transformation matrices for seamless integration of point cloud data with other sensor data or pre-existing 3D models.

Reference
#########

.. tabs::

.. tab:: Python

.. autoclass:: depthai.PointCloudConfig
:members:
:inherited-members:
:noindex:

.. tab:: C++

.. doxygenclass:: dai::PointCloudConfig
:project: depthai-core
:members:
:private-members:
:undoc-members:

.. include:: ../../includes/footer-short.rst
31 changes: 31 additions & 0 deletions docs/source/components/messages/pointcloud_data.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
PointCloudData
==============

:ref:`PointCloudData` encapsulates 3D spatial information, representing a collection of points in a 3D space. Each point within the point cloud has its own position (X, Y, Z coordinates).
PointCloudData is used to represent the output of :ref:`PointCloud` nodes, and can be used to perform a variety of spatial analysis and reconstruction tasks.

Setter methods are only used to provide metadata to the :ref:`PointCloudData` message (will be used for recording and replaying pointclouds).

Reference
#########

The detailed API for `PointCloudData` offers control over the generation, manipulation, and retrieval of 3D point cloud data.

.. tabs::

.. tab:: Python

.. autoclass:: depthai.PointCloudData
:members:
:inherited-members:
:noindex:

.. tab:: C++

.. doxygenclass:: dai::PointCloudData
:project: depthai-core
:members:
:private-members:
:undoc-members:

.. include:: ../../includes/footer-short.rst
154 changes: 154 additions & 0 deletions docs/source/components/nodes/pointcloud.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,154 @@
PointCloud
==========

The PointCloud node enables on-device point cloud generation from depth map.

How to place it
###############

.. tabs::

.. code-tab:: py

pipeline = dai.Pipeline()
pointCloud = pipeline.create(dai.node.PointCloud)

.. code-tab:: c++

dai::Pipeline pipeline;
auto pointCloud = pipeline.create<dai::node::PointCloud>();


Inputs and Outputs
##################

.. code-block::
┌─────────────────────┐
│ │
inputConfig │ PointCloud │
──────────────►│ │ outputPointCloud
│ ├────────────────►
inputDepth │ │ passthroughDepth
──────────────►│---------------------├────────────────►
└─────────────────────┘
**Message types**

- :code:`inputDepth` - :ref:`ImgFrame`
- :code:`inputConfig` - :ref:`PointCloudConfig`
- :code:`outputPointCloud` - :ref:`PointCloudData`
- :code:`passthroughDepth` - :ref:`ImgFrame` (passthrough input depth map)


Example visualization with Open3D
#################################

.. tabs::

.. code-tab:: py

import open3d as o3d
import numpy as np
import depthai as dai

pcd = o3d.geometry.PointCloud()
vis = o3d.visualization.VisualizerWithKeyCallback()
vis.create_window()

with dai.Device(pipeline) as device:
coordinateFrame = o3d.geometry.TriangleMesh.create_coordinate_frame(size=1000, origin=[0,0,0])
vis.add_geometry(coordinateFrame)

while device.isPipelineRunning():
inMessage = q.get()
inColor = inMessage["rgb"]
inPointCloud = inMessage["pcl"]
cvColorFrame = inColor.getCvFrame()

if inPointCloud:
points = inPointCloud.getPoints().astype(np.float64)
pcd.points = o3d.utility.Vector3dVector(points)
colors = (cvRGBFrame.reshape(-1, 3) / 255.0).astype(np.float64)
pcd.colors = o3d.utility.Vector3dVector(colors)
vis.update_geometry(pcd)

vis.poll_events()
vis.update_renderer()

vis.destroy_window()


.. code-tab:: c++

#include <iostream>
#include <open3d/Open3D.h>
#include <depthai/depthai.hpp>

int main() {
auto viewer = std::make_unique<pcl::visualization::PCLVisualizer>("Cloud Viewer");
viewer->addPointCloud<pcl::PointXYZ>(cloud, "cloud");

dai::Device device(pipeline);

auto q = device.getOutputQueue("out", 8, false);
auto qDepth = device.getOutputQueue("depth", 8, false);

while(true) {
std::cout << "Waiting for data" << std::endl;
auto depthImg = qDepth->get<dai::ImgFrame>();
auto pclMsg = q->get<dai::PointCloudData>();

if(!pclMsg) {
std::cout << "No data" << std::endl;
continue;
}

auto frame = depthImg->getCvFrame();
frame.convertTo(frame, CV_8UC1, 255 / depth->initialConfig.getMaxDisparity());

if(pclMsg->getPoints().empty()) {
std::cout << "Empty point cloud" << std::endl;
continue;
}

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = pclMsg->getPclData();
viewer->updatePointCloud(cloud, "cloud");

viewer->spinOnce(10);

if(viewer->wasStopped()) {
break;
}
}


Examples using PointCloud
#########################

- :ref:`PointCloud Visualization`
- :ref:`PointCloud Control`


Reference
#########

.. tabs::

.. tab:: Python

.. autoclass:: depthai.node.PointCloud
:members:
:inherited-members:
:noindex:

.. tab:: C++

.. doxygenclass:: dai::node::PointCloud
:project: depthai-core
:members:
:private-members:
:undoc-members:


.. include:: ../../includes/footer-short.rst
60 changes: 60 additions & 0 deletions docs/source/samples/PointCloud/pointcloud_control.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
PointCloud Control
==================

This example demonstrates how to use :ref:`PointCloudConfig` message to dynamically update the transformation matrix of a point cloud and visualize the transformed point cloud using Open3D.

The transformation matrix is updated to make it look like the point cloud is rotating about the Z-axis. This is achieved by first moving the pointcloud along Y axis:

.. code-block:: python
# Move the point cloud along Y axis
translate_y_matrix = np.array([[1, 0, 0, 0],
[0, 1, 0, 500],
[0, 0, 1, 0],
[0, 0, 0, 1]])
Then, the point cloud is rotated about Z axis:

.. code-block:: python
# Rotate the point cloud about Z axis
rotate_z_matrix = np.array([[np.cos(angle), -np.sin(angle), 0, 0],
[np.sin(angle), np.cos(angle), 0, 0],
[0, 0, 1, 0],
[0, 0, 0, 1]])
Demo
####

.. image:: /_static/images/examples/pointcloud_control.gif
:alt: PointCloud control

Setup
#####

Ensure DepthAI and Open3D are installed in your Python environment:

.. code-block:: bash
python3 -m pip install depthai open3d
Source code
###########

The example initializes the DepthAI pipeline with color and mono cameras and a stereo depth node to generate depth information. It then creates a point cloud node, dynamically updates its transformation matrix based on a rotation value, and visualizes this transformed point cloud using Open3D. Each point's color corresponds to the color image captured by the RGB camera.

.. tabs::

.. tab:: Python

Also `available on GitHub <https://github.com/luxonis/depthai-python/blob/main/examples/PointCloud/pointcloud_control.py>`__

.. literalinclude:: ../../../../examples/PointCloud/pointcloud_control.py
:language: python
:linenos:


.. include:: /includes/footer-short.rst
Loading

0 comments on commit cf41a43

Please sign in to comment.